mirror of https://github.com/lumapu/ahoy.git
56 changed files with 3067 additions and 728 deletions
@ -0,0 +1,981 @@ |
|||
diff --git a/RF24.cpp b/RF24.cpp
|
|||
index c0cc732..b6708d9 100644
|
|||
--- a/RF24.cpp
|
|||
+++ b/RF24.cpp
|
|||
@@ -12,228 +12,24 @@
|
|||
|
|||
/****************************************************************************/ |
|||
|
|||
-void RF24::csn(bool mode)
|
|||
-{
|
|||
-#if defined(RF24_TINY)
|
|||
- if (ce_pin != csn_pin) {
|
|||
- digitalWrite(csn_pin, mode);
|
|||
- }
|
|||
- else {
|
|||
- if (mode == HIGH) {
|
|||
- PORTB |= (1 << PINB2); // SCK->CSN HIGH
|
|||
- delayMicroseconds(RF24_CSN_SETTLE_HIGH_DELAY); // allow csn to settle.
|
|||
- }
|
|||
- else {
|
|||
- PORTB &= ~(1 << PINB2); // SCK->CSN LOW
|
|||
- delayMicroseconds(RF24_CSN_SETTLE_LOW_DELAY); // allow csn to settle
|
|||
- }
|
|||
- }
|
|||
- // Return, CSN toggle complete
|
|||
- return;
|
|||
-
|
|||
-#elif defined(ARDUINO) && !defined(RF24_SPI_TRANSACTIONS)
|
|||
- // Minimum ideal SPI bus speed is 2x data rate
|
|||
- // If we assume 2Mbs data rate and 16Mhz clock, a
|
|||
- // divider of 4 is the minimum we want.
|
|||
- // CLK:BUS 8Mhz:2Mhz, 16Mhz:4Mhz, or 20Mhz:5Mhz
|
|||
-
|
|||
- #if !defined(SOFTSPI)
|
|||
- // applies to SPI_UART and inherent hardware SPI
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- _spi->setBitOrder(MSBFIRST);
|
|||
- _spi->setDataMode(SPI_MODE0);
|
|||
-
|
|||
- #if !defined(F_CPU) || F_CPU < 20000000
|
|||
- _spi->setClockDivider(SPI_CLOCK_DIV2);
|
|||
- #elif F_CPU < 40000000
|
|||
- _spi->setClockDivider(SPI_CLOCK_DIV4);
|
|||
- #elif F_CPU < 80000000
|
|||
- _spi->setClockDivider(SPI_CLOCK_DIV8);
|
|||
- #elif F_CPU < 160000000
|
|||
- _spi->setClockDivider(SPI_CLOCK_DIV16);
|
|||
- #elif F_CPU < 320000000
|
|||
- _spi->setClockDivider(SPI_CLOCK_DIV32);
|
|||
- #elif F_CPU < 640000000
|
|||
- _spi->setClockDivider(SPI_CLOCK_DIV64);
|
|||
- #elif F_CPU < 1280000000
|
|||
- _spi->setClockDivider(SPI_CLOCK_DIV128);
|
|||
- #else // F_CPU >= 1280000000
|
|||
- #error "Unsupported CPU frequency. Please set correct SPI divider."
|
|||
- #endif // F_CPU to SPI_CLOCK_DIV translation
|
|||
-
|
|||
- #else // !defined(RF24_SPI_PTR)
|
|||
- _SPI.setBitOrder(MSBFIRST);
|
|||
- _SPI.setDataMode(SPI_MODE0);
|
|||
-
|
|||
- #if !defined(F_CPU) || F_CPU < 20000000
|
|||
- _SPI.setClockDivider(SPI_CLOCK_DIV2);
|
|||
- #elif F_CPU < 40000000
|
|||
- _SPI.setClockDivider(SPI_CLOCK_DIV4);
|
|||
- #elif F_CPU < 80000000
|
|||
- _SPI.setClockDivider(SPI_CLOCK_DIV8);
|
|||
- #elif F_CPU < 160000000
|
|||
- _SPI.setClockDivider(SPI_CLOCK_DIV16);
|
|||
- #elif F_CPU < 320000000
|
|||
- _SPI.setClockDivider(SPI_CLOCK_DIV32);
|
|||
- #elif F_CPU < 640000000
|
|||
- _SPI.setClockDivider(SPI_CLOCK_DIV64);
|
|||
- #elif F_CPU < 1280000000
|
|||
- _SPI.setClockDivider(SPI_CLOCK_DIV128);
|
|||
- #else // F_CPU >= 1280000000
|
|||
- #error "Unsupported CPU frequency. Please set correct SPI divider."
|
|||
- #endif // F_CPU to SPI_CLOCK_DIV translation
|
|||
- #endif // !defined(RF24_SPI_PTR)
|
|||
- #endif // !defined(SOFTSPI)
|
|||
-
|
|||
-#elif defined(RF24_RPi)
|
|||
- if (!mode)
|
|||
- _SPI.chipSelect(csn_pin);
|
|||
-#endif // defined(RF24_RPi)
|
|||
-
|
|||
-#if !defined(RF24_LINUX)
|
|||
- digitalWrite(csn_pin, mode);
|
|||
- delayMicroseconds(csDelay);
|
|||
-#else
|
|||
- static_cast<void>(mode); // ignore -Wunused-parameter
|
|||
-#endif // !defined(RF24_LINUX)
|
|||
-}
|
|||
-
|
|||
-/****************************************************************************/
|
|||
-
|
|||
void RF24::ce(bool level) |
|||
{ |
|||
-#ifndef RF24_LINUX
|
|||
- //Allow for 3-pin use on ATTiny
|
|||
- if (ce_pin != csn_pin) {
|
|||
-#endif
|
|||
- digitalWrite(ce_pin, level);
|
|||
-#ifndef RF24_LINUX
|
|||
- }
|
|||
-#endif
|
|||
-}
|
|||
-
|
|||
-/****************************************************************************/
|
|||
-
|
|||
-inline void RF24::beginTransaction()
|
|||
-{
|
|||
-#if defined(RF24_SPI_TRANSACTIONS)
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- #if defined(RF24_RP2)
|
|||
- _spi->beginTransaction(spi_speed);
|
|||
- #else // ! defined (RF24_RP2)
|
|||
- _spi->beginTransaction(SPISettings(spi_speed, MSBFIRST, SPI_MODE0));
|
|||
- #endif // ! defined (RF24_RP2)
|
|||
- #else // !defined(RF24_SPI_PTR)
|
|||
- _SPI.beginTransaction(SPISettings(spi_speed, MSBFIRST, SPI_MODE0));
|
|||
- #endif // !defined(RF24_SPI_PTR)
|
|||
-#endif // defined (RF24_SPI_TRANSACTIONS)
|
|||
- csn(LOW);
|
|||
-}
|
|||
-
|
|||
-/****************************************************************************/
|
|||
-
|
|||
-inline void RF24::endTransaction()
|
|||
-{
|
|||
- csn(HIGH);
|
|||
-#if defined(RF24_SPI_TRANSACTIONS)
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- _spi->endTransaction();
|
|||
- #else // !defined(RF24_SPI_PTR)
|
|||
- _SPI.endTransaction();
|
|||
- #endif // !defined(RF24_SPI_PTR)
|
|||
-#endif // defined (RF24_SPI_TRANSACTIONS)
|
|||
+ hal->ce(level);
|
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
|
|||
void RF24::read_register(uint8_t reg, uint8_t* buf, uint8_t len) |
|||
{ |
|||
-#if defined(RF24_LINUX) || defined(RF24_RP2)
|
|||
- beginTransaction(); //configures the spi settings for RPi, locks mutex and setting csn low
|
|||
- uint8_t* prx = spi_rxbuff;
|
|||
- uint8_t* ptx = spi_txbuff;
|
|||
- uint8_t size = static_cast<uint8_t>(len + 1); // Add register value to transmit buffer
|
|||
-
|
|||
- *ptx++ = (R_REGISTER | reg);
|
|||
-
|
|||
- while (len--) {
|
|||
- *ptx++ = RF24_NOP; // Dummy operation, just for reading
|
|||
- }
|
|||
-
|
|||
- #if defined(RF24_RP2)
|
|||
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, size);
|
|||
- #else // !defined (RF24_RP2)
|
|||
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), size);
|
|||
- #endif // !defined (RF24_RP2)
|
|||
-
|
|||
- status = *prx++; // status is 1st byte of receive buffer
|
|||
-
|
|||
- // decrement before to skip status byte
|
|||
- while (--size) {
|
|||
- *buf++ = *prx++;
|
|||
- }
|
|||
-
|
|||
- endTransaction(); // unlocks mutex and setting csn high
|
|||
-
|
|||
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
-
|
|||
- beginTransaction();
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- status = _spi->transfer(R_REGISTER | reg);
|
|||
- while (len--) {
|
|||
- *buf++ = _spi->transfer(0xFF);
|
|||
- }
|
|||
-
|
|||
- #else // !defined(RF24_SPI_PTR)
|
|||
- status = _SPI.transfer(R_REGISTER | reg);
|
|||
- while (len--) {
|
|||
- *buf++ = _SPI.transfer(0xFF);
|
|||
- }
|
|||
-
|
|||
- #endif // !defined(RF24_SPI_PTR)
|
|||
- endTransaction();
|
|||
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
+ status = hal->read(R_REGISTER | reg, buf, len);
|
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
|
|||
uint8_t RF24::read_register(uint8_t reg) |
|||
{ |
|||
- uint8_t result;
|
|||
-
|
|||
-#if defined(RF24_LINUX) || defined(RF24_RP2)
|
|||
- beginTransaction();
|
|||
-
|
|||
- uint8_t* prx = spi_rxbuff;
|
|||
- uint8_t* ptx = spi_txbuff;
|
|||
- *ptx++ = (R_REGISTER | reg);
|
|||
- *ptx++ = RF24_NOP; // Dummy operation, just for reading
|
|||
-
|
|||
- #if defined(RF24_RP2)
|
|||
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, 2);
|
|||
- #else // !defined(RF24_RP2)
|
|||
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), 2);
|
|||
- #endif // !defined(RF24_RP2)
|
|||
-
|
|||
- status = *prx; // status is 1st byte of receive buffer
|
|||
- result = *++prx; // result is 2nd byte of receive buffer
|
|||
-
|
|||
- endTransaction();
|
|||
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
-
|
|||
- beginTransaction();
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- status = _spi->transfer(R_REGISTER | reg);
|
|||
- result = _spi->transfer(0xff);
|
|||
-
|
|||
- #else // !defined(RF24_SPI_PTR)
|
|||
- status = _SPI.transfer(R_REGISTER | reg);
|
|||
- result = _SPI.transfer(0xff);
|
|||
-
|
|||
- #endif // !defined(RF24_SPI_PTR)
|
|||
- endTransaction();
|
|||
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
-
|
|||
+ uint8_t result = 0xff;
|
|||
+ status = hal->read(R_REGISTER | reg, &result, sizeof(result));
|
|||
return result; |
|||
} |
|||
|
|||
@@ -241,43 +37,7 @@ uint8_t RF24::read_register(uint8_t reg)
|
|||
|
|||
void RF24::write_register(uint8_t reg, const uint8_t* buf, uint8_t len) |
|||
{ |
|||
-#if defined(RF24_LINUX) || defined(RF24_RP2)
|
|||
- beginTransaction();
|
|||
- uint8_t* prx = spi_rxbuff;
|
|||
- uint8_t* ptx = spi_txbuff;
|
|||
- uint8_t size = static_cast<uint8_t>(len + 1); // Add register value to transmit buffer
|
|||
-
|
|||
- *ptx++ = (W_REGISTER | (REGISTER_MASK & reg));
|
|||
- while (len--) {
|
|||
- *ptx++ = *buf++;
|
|||
- }
|
|||
-
|
|||
- #if defined(RF24_RP2)
|
|||
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, size);
|
|||
- #else // !defined(RF24_RP2)
|
|||
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), size);
|
|||
- #endif // !defined(RF24_RP2)
|
|||
-
|
|||
- status = *prx; // status is 1st byte of receive buffer
|
|||
- endTransaction();
|
|||
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
-
|
|||
- beginTransaction();
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- status = _spi->transfer(W_REGISTER | reg);
|
|||
- while (len--) {
|
|||
- _spi->transfer(*buf++);
|
|||
- }
|
|||
-
|
|||
- #else // !defined(RF24_SPI_PTR)
|
|||
- status = _SPI.transfer(W_REGISTER | reg);
|
|||
- while (len--) {
|
|||
- _SPI.transfer(*buf++);
|
|||
- }
|
|||
-
|
|||
- #endif // !defined(RF24_SPI_PTR)
|
|||
- endTransaction();
|
|||
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
+ status = hal->write(W_REGISTER | reg, buf, len);
|
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
@@ -288,47 +48,11 @@ void RF24::write_register(uint8_t reg, uint8_t value, bool is_cmd_only)
|
|||
if (reg != RF24_NOP) { // don't print the get_status() operation |
|||
IF_SERIAL_DEBUG(printf_P(PSTR("write_register(%02x)\r\n"), reg)); |
|||
} |
|||
- beginTransaction();
|
|||
-#if defined(RF24_LINUX)
|
|||
- status = _SPI.transfer(W_REGISTER | reg);
|
|||
-#else // !defined(RF24_LINUX) || defined (RF24_RP2)
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- status = _spi->transfer(W_REGISTER | reg);
|
|||
- #else // !defined (RF24_SPI_PTR)
|
|||
- status = _SPI.transfer(W_REGISTER | reg);
|
|||
- #endif // !defined (RF24_SPI_PTR)
|
|||
-#endif // !defined(RF24_LINUX) || defined(RF24_RP2)
|
|||
- endTransaction();
|
|||
+ status = hal->write(W_REGISTER | reg, nullptr, 0);
|
|||
} |
|||
else { |
|||
IF_SERIAL_DEBUG(printf_P(PSTR("write_register(%02x,%02x)\r\n"), reg, value)); |
|||
-#if defined(RF24_LINUX) || defined(RF24_RP2)
|
|||
- beginTransaction();
|
|||
- uint8_t* prx = spi_rxbuff;
|
|||
- uint8_t* ptx = spi_txbuff;
|
|||
- *ptx++ = (W_REGISTER | reg);
|
|||
- *ptx = value;
|
|||
-
|
|||
- #if defined(RF24_RP2)
|
|||
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, 2);
|
|||
- #else // !defined(RF24_RP2)
|
|||
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), 2);
|
|||
- #endif // !defined(RF24_RP2)
|
|||
-
|
|||
- status = *prx++; // status is 1st byte of receive buffer
|
|||
- endTransaction();
|
|||
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
-
|
|||
- beginTransaction();
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- status = _spi->transfer(W_REGISTER | reg);
|
|||
- _spi->transfer(value);
|
|||
- #else // !defined(RF24_SPI_PTR)
|
|||
- status = _SPI.transfer(W_REGISTER | reg);
|
|||
- _SPI.transfer(value);
|
|||
- #endif // !defined(RF24_SPI_PTR)
|
|||
- endTransaction();
|
|||
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
+ status = hal->write(W_REGISTER | reg, &value, sizeof(value));
|
|||
} |
|||
} |
|||
|
|||
@@ -347,60 +71,8 @@ void RF24::write_payload(const void* buf, uint8_t data_len, const uint8_t writeT
|
|||
data_len = rf24_min(data_len, static_cast<uint8_t>(32)); |
|||
} |
|||
|
|||
- //printf("[Writing %u bytes %u blanks]",data_len,blank_len);
|
|||
IF_SERIAL_DEBUG(printf("[Writing %u bytes %u blanks]\n", data_len, blank_len);); |
|||
-
|
|||
-#if defined(RF24_LINUX) || defined(RF24_RP2)
|
|||
- beginTransaction();
|
|||
- uint8_t* prx = spi_rxbuff;
|
|||
- uint8_t* ptx = spi_txbuff;
|
|||
- uint8_t size;
|
|||
- size = static_cast<uint8_t>(data_len + blank_len + 1); // Add register value to transmit buffer
|
|||
-
|
|||
- *ptx++ = writeType;
|
|||
- while (data_len--) {
|
|||
- *ptx++ = *current++;
|
|||
- }
|
|||
-
|
|||
- while (blank_len--) {
|
|||
- *ptx++ = 0;
|
|||
- }
|
|||
-
|
|||
- #if defined(RF24_RP2)
|
|||
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, size);
|
|||
- #else // !defined(RF24_RP2)
|
|||
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), size);
|
|||
- #endif // !defined(RF24_RP2)
|
|||
-
|
|||
- status = *prx; // status is 1st byte of receive buffer
|
|||
- endTransaction();
|
|||
-
|
|||
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
-
|
|||
- beginTransaction();
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- status = _spi->transfer(writeType);
|
|||
- while (data_len--) {
|
|||
- _spi->transfer(*current++);
|
|||
- }
|
|||
-
|
|||
- while (blank_len--) {
|
|||
- _spi->transfer(0);
|
|||
- }
|
|||
-
|
|||
- #else // !defined(RF24_SPI_PTR)
|
|||
- status = _SPI.transfer(writeType);
|
|||
- while (data_len--) {
|
|||
- _SPI.transfer(*current++);
|
|||
- }
|
|||
-
|
|||
- while (blank_len--) {
|
|||
- _SPI.transfer(0);
|
|||
- }
|
|||
-
|
|||
- #endif // !defined(RF24_SPI_PTR)
|
|||
- endTransaction();
|
|||
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
+ status = hal->write(writeType, current, data_len, blank_len);
|
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
@@ -421,65 +93,7 @@ void RF24::read_payload(void* buf, uint8_t data_len)
|
|||
//printf("[Reading %u bytes %u blanks]",data_len,blank_len); |
|||
|
|||
IF_SERIAL_DEBUG(printf("[Reading %u bytes %u blanks]\n", data_len, blank_len);); |
|||
-
|
|||
-#if defined(RF24_LINUX) || defined(RF24_RP2)
|
|||
- beginTransaction();
|
|||
- uint8_t* prx = spi_rxbuff;
|
|||
- uint8_t* ptx = spi_txbuff;
|
|||
- uint8_t size;
|
|||
- size = static_cast<uint8_t>(data_len + blank_len + 1); // Add register value to transmit buffer
|
|||
-
|
|||
- *ptx++ = R_RX_PAYLOAD;
|
|||
- while (--size) {
|
|||
- *ptx++ = RF24_NOP;
|
|||
- }
|
|||
-
|
|||
- size = static_cast<uint8_t>(data_len + blank_len + 1); // Size has been lost during while, re affect
|
|||
-
|
|||
- #if defined(RF24_RP2)
|
|||
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, size);
|
|||
- #else // !defined(RF24_RP2)
|
|||
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), size);
|
|||
- #endif // !defined(RF24_RP2)
|
|||
-
|
|||
- status = *prx++; // 1st byte is status
|
|||
-
|
|||
- if (data_len > 0) {
|
|||
- // Decrement before to skip 1st status byte
|
|||
- while (--data_len) {
|
|||
- *current++ = *prx++;
|
|||
- }
|
|||
-
|
|||
- *current = *prx;
|
|||
- }
|
|||
- endTransaction();
|
|||
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
-
|
|||
- beginTransaction();
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- status = _spi->transfer(R_RX_PAYLOAD);
|
|||
- while (data_len--) {
|
|||
- *current++ = _spi->transfer(0xFF);
|
|||
- }
|
|||
-
|
|||
- while (blank_len--) {
|
|||
- _spi->transfer(0xFF);
|
|||
- }
|
|||
-
|
|||
- #else // !defined(RF24_SPI_PTR)
|
|||
- status = _SPI.transfer(R_RX_PAYLOAD);
|
|||
- while (data_len--) {
|
|||
- *current++ = _SPI.transfer(0xFF);
|
|||
- }
|
|||
-
|
|||
- while (blank_len--) {
|
|||
- _SPI.transfer(0xff);
|
|||
- }
|
|||
-
|
|||
- #endif // !defined(RF24_SPI_PTR)
|
|||
- endTransaction();
|
|||
-
|
|||
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
|
|||
+ status = hal->read(R_RX_PAYLOAD, current, data_len, blank_len);
|
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
@@ -577,16 +191,16 @@ uint8_t RF24::sprintf_address_register(char* out_buffer, uint8_t reg, uint8_t qt
|
|||
|
|||
/****************************************************************************/ |
|||
|
|||
-RF24::RF24(rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin, uint32_t _spi_speed)
|
|||
- : ce_pin(_cepin), csn_pin(_cspin), spi_speed(_spi_speed), payload_size(32), _is_p_variant(false), _is_p0_rx(false), addr_width(5), dynamic_payloads_enabled(true), csDelay(5)
|
|||
+RF24::RF24(RF24_hal* _hal)
|
|||
+ : hal(_hal), payload_size(32), _is_p_variant(false), _is_p0_rx(false), addr_width(5), dynamic_payloads_enabled(true), csDelay(5)
|
|||
{ |
|||
_init_obj(); |
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
|
|||
-RF24::RF24(uint32_t _spi_speed)
|
|||
- : ce_pin(RF24_PIN_INVALID), csn_pin(RF24_PIN_INVALID), spi_speed(_spi_speed), payload_size(32), _is_p_variant(false), _is_p0_rx(false), addr_width(5), dynamic_payloads_enabled(true), csDelay(5)
|
|||
+RF24::RF24()
|
|||
+ : hal(nullptr), payload_size(32), _is_p_variant(false), _is_p0_rx(false), addr_width(5), dynamic_payloads_enabled(true), csDelay(5)
|
|||
{ |
|||
_init_obj(); |
|||
} |
|||
@@ -595,16 +209,7 @@ RF24::RF24(uint32_t _spi_speed)
|
|||
|
|||
void RF24::_init_obj() |
|||
{ |
|||
- // Use a pointer on the Arduino platform
|
|||
-
|
|||
-#if defined(RF24_SPI_PTR) && !defined(RF24_RP2)
|
|||
- _spi = &SPI;
|
|||
-#endif // defined (RF24_SPI_PTR)
|
|||
-
|
|||
pipe0_reading_address[0] = 0; |
|||
- if (spi_speed <= 35000) { //Handle old BCM2835 speed constants, default to RF24_SPI_SPEED
|
|||
- spi_speed = RF24_SPI_SPEED;
|
|||
- }
|
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
@@ -677,19 +282,6 @@ static const PROGMEM char* const rf24_pa_dbm_e_str_P[] = {
|
|||
rf24_pa_dbm_e_str_3, |
|||
}; |
|||
|
|||
- #if defined(RF24_LINUX)
|
|||
-static const char rf24_csn_e_str_0[] = "CE0 (PI Hardware Driven)";
|
|||
-static const char rf24_csn_e_str_1[] = "CE1 (PI Hardware Driven)";
|
|||
-static const char rf24_csn_e_str_2[] = "CE2 (PI Hardware Driven)";
|
|||
-static const char rf24_csn_e_str_3[] = "Custom GPIO Software Driven";
|
|||
-static const char* const rf24_csn_e_str_P[] = {
|
|||
- rf24_csn_e_str_0,
|
|||
- rf24_csn_e_str_1,
|
|||
- rf24_csn_e_str_2,
|
|||
- rf24_csn_e_str_3,
|
|||
-};
|
|||
- #endif // defined(RF24_LINUX)
|
|||
-
|
|||
static const PROGMEM char rf24_feature_e_str_on[] = "= Enabled"; |
|||
static const PROGMEM char rf24_feature_e_str_allowed[] = "= Allowed"; |
|||
static const PROGMEM char rf24_feature_e_str_open[] = " open "; |
|||
@@ -704,19 +296,6 @@ static const PROGMEM char* const rf24_feature_e_str_P[] = {
|
|||
|
|||
void RF24::printDetails(void) |
|||
{ |
|||
-
|
|||
- #if defined(RF24_LINUX)
|
|||
- printf("================ SPI Configuration ================\n");
|
|||
- uint8_t bus_ce = static_cast<uint8_t>(csn_pin % 10);
|
|||
- uint8_t bus_numb = static_cast<uint8_t>((csn_pin - bus_ce) / 10);
|
|||
- printf("CSN Pin\t\t= /dev/spidev%d.%d\n", bus_numb, bus_ce);
|
|||
- printf("CE Pin\t\t= Custom GPIO%d\n", ce_pin);
|
|||
- #endif
|
|||
- printf_P(PSTR("SPI Speedz\t= %d Mhz\n"), static_cast<uint8_t>(spi_speed / 1000000)); //Print the SPI speed on non-Linux devices
|
|||
- #if defined(RF24_LINUX)
|
|||
- printf("================ NRF Configuration ================\n");
|
|||
- #endif // defined(RF24_LINUX)
|
|||
-
|
|||
print_status(get_status()); |
|||
|
|||
print_address_register(PSTR("RX_ADDR_P0-1"), RX_ADDR_P0, 2); |
|||
@@ -748,19 +327,6 @@ void RF24::printDetails(void)
|
|||
|
|||
void RF24::printPrettyDetails(void) |
|||
{ |
|||
-
|
|||
- #if defined(RF24_LINUX)
|
|||
- printf("================ SPI Configuration ================\n");
|
|||
- uint8_t bus_ce = static_cast<uint8_t>(csn_pin % 10);
|
|||
- uint8_t bus_numb = static_cast<uint8_t>((csn_pin - bus_ce) / 10);
|
|||
- printf("CSN Pin\t\t\t= /dev/spidev%d.%d\n", bus_numb, bus_ce);
|
|||
- printf("CE Pin\t\t\t= Custom GPIO%d\n", ce_pin);
|
|||
- #endif
|
|||
- printf_P(PSTR("SPI Frequency\t\t= %d Mhz\n"), static_cast<uint8_t>(spi_speed / 1000000)); //Print the SPI speed on non-Linux devices
|
|||
- #if defined(RF24_LINUX)
|
|||
- printf("================ NRF Configuration ================\n");
|
|||
- #endif // defined(RF24_LINUX)
|
|||
-
|
|||
uint8_t channel = getChannel(); |
|||
uint16_t frequency = static_cast<uint16_t>(channel + 2400); |
|||
printf_P(PSTR("Channel\t\t\t= %u (~ %u MHz)\r\n"), channel, frequency); |
|||
@@ -846,11 +412,6 @@ void RF24::printPrettyDetails(void)
|
|||
uint16_t RF24::sprintfPrettyDetails(char* debugging_information) |
|||
{ |
|||
const char* format_string = PSTR( |
|||
- "================ SPI Configuration ================\n"
|
|||
- "CSN Pin\t\t\t= %d\n"
|
|||
- "CE Pin\t\t\t= %d\n"
|
|||
- "SPI Frequency\t\t= %d Mhz\n"
|
|||
- "================ NRF Configuration ================\n"
|
|||
"Channel\t\t\t= %u (~ %u MHz)\n" |
|||
"RF Data Rate\t\t" PRIPSTR "\n" |
|||
"RF Power Amplifier\t" PRIPSTR "\n" |
|||
@@ -870,8 +431,7 @@ uint16_t RF24::sprintfPrettyDetails(char* debugging_information)
|
|||
const char* format_str3 = PSTR("\nPipe %d (" PRIPSTR ") bound\t= 0x"); |
|||
|
|||
uint16_t offset = sprintf_P( |
|||
- debugging_information, format_string, csn_pin, ce_pin,
|
|||
- static_cast<uint8_t>(spi_speed / 1000000), getChannel(),
|
|||
+ debugging_information, format_string, getChannel(),
|
|||
static_cast<uint16_t>(getChannel() + 2400), |
|||
(char*)(pgm_read_ptr(&rf24_datarate_e_str_P[getDataRate()])), |
|||
(char*)(pgm_read_ptr(&rf24_pa_dbm_e_str_P[getPALevel()])), |
|||
@@ -940,87 +500,26 @@ void RF24::encodeRadioDetails(uint8_t* encoded_details)
|
|||
*encoded_details++ = read_register(i); |
|||
} |
|||
} |
|||
- *encoded_details++ = ce_pin >> 4;
|
|||
- *encoded_details++ = ce_pin & 0xFF;
|
|||
- *encoded_details++ = csn_pin >> 4;
|
|||
- *encoded_details++ = csn_pin & 0xFF;
|
|||
- *encoded_details = static_cast<uint8_t>((spi_speed / 1000000) | _BV(_is_p_variant * 4));
|
|||
} |
|||
#endif // !defined(MINIMAL) |
|||
|
|||
/****************************************************************************/ |
|||
-#if defined(RF24_SPI_PTR) || defined(DOXYGEN_FORCED)
|
|||
-// does not apply to RF24_LINUX
|
|||
|
|||
-bool RF24::begin(_SPI* spiBus)
|
|||
+bool RF24::begin(void)
|
|||
{ |
|||
- _spi = spiBus;
|
|||
return _init_pins() && _init_radio(); |
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
|
|||
-bool RF24::begin(_SPI* spiBus, rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin)
|
|||
+bool RF24::begin(RF24_hal* _hal)
|
|||
{ |
|||
- ce_pin = _cepin;
|
|||
- csn_pin = _cspin;
|
|||
- return begin(spiBus);
|
|||
-}
|
|||
-
|
|||
-#endif // defined (RF24_SPI_PTR) || defined (DOXYGEN_FORCED)
|
|||
-
|
|||
-/****************************************************************************/
|
|||
-
|
|||
-bool RF24::begin(rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin)
|
|||
-{
|
|||
- ce_pin = _cepin;
|
|||
- csn_pin = _cspin;
|
|||
+ hal = _hal;
|
|||
return begin(); |
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
|
|||
-bool RF24::begin(void)
|
|||
-{
|
|||
-#if defined(RF24_LINUX)
|
|||
- #if defined(RF24_RPi)
|
|||
- switch (csn_pin) { // Ensure valid hardware CS pin
|
|||
- case 0: break;
|
|||
- case 1: break;
|
|||
- // Allow BCM2835 enums for RPi
|
|||
- case 8: csn_pin = 0; break;
|
|||
- case 7: csn_pin = 1; break;
|
|||
- case 18: csn_pin = 10; break; // to make it work on SPI1
|
|||
- case 17: csn_pin = 11; break;
|
|||
- case 16: csn_pin = 12; break;
|
|||
- default: csn_pin = 0; break;
|
|||
- }
|
|||
- #endif // RF24_RPi
|
|||
-
|
|||
- _SPI.begin(csn_pin, spi_speed);
|
|||
-
|
|||
-#elif defined(XMEGA_D3)
|
|||
- _spi->begin(csn_pin);
|
|||
-
|
|||
-#elif defined(RF24_RP2)
|
|||
- _spi = new SPI();
|
|||
- _spi->begin(PICO_DEFAULT_SPI ? spi1 : spi0);
|
|||
-
|
|||
-#else // using an Arduino platform || defined (LITTLEWIRE)
|
|||
-
|
|||
- #if defined(RF24_SPI_PTR)
|
|||
- _spi->begin();
|
|||
- #else // !defined(RF24_SPI_PTR)
|
|||
- _SPI.begin();
|
|||
- #endif // !defined(RF24_SPI_PTR)
|
|||
-
|
|||
-#endif // !defined(XMEGA_D3) && !defined(RF24_LINUX)
|
|||
-
|
|||
- return _init_pins() && _init_radio();
|
|||
-}
|
|||
-
|
|||
-/****************************************************************************/
|
|||
-
|
|||
bool RF24::_init_pins() |
|||
{ |
|||
if (!isValid()) { |
|||
@@ -1028,46 +527,7 @@ bool RF24::_init_pins()
|
|||
return false; |
|||
} |
|||
|
|||
-#if defined(RF24_LINUX)
|
|||
-
|
|||
- #if defined(MRAA)
|
|||
- GPIO();
|
|||
- gpio.begin(ce_pin, csn_pin);
|
|||
- #endif
|
|||
-
|
|||
- pinMode(ce_pin, OUTPUT);
|
|||
- ce(LOW);
|
|||
- delay(100);
|
|||
-
|
|||
-#elif defined(LITTLEWIRE)
|
|||
- pinMode(csn_pin, OUTPUT);
|
|||
- csn(HIGH);
|
|||
-
|
|||
-#elif defined(XMEGA_D3)
|
|||
- if (ce_pin != csn_pin) {
|
|||
- pinMode(ce_pin, OUTPUT);
|
|||
- };
|
|||
- ce(LOW);
|
|||
- csn(HIGH);
|
|||
- delay(200);
|
|||
-
|
|||
-#else // using an Arduino platform
|
|||
-
|
|||
- // Initialize pins
|
|||
- if (ce_pin != csn_pin) {
|
|||
- pinMode(ce_pin, OUTPUT);
|
|||
- pinMode(csn_pin, OUTPUT);
|
|||
- }
|
|||
-
|
|||
- ce(LOW);
|
|||
- csn(HIGH);
|
|||
-
|
|||
- #if defined(__ARDUINO_X86__)
|
|||
- delay(100);
|
|||
- #endif
|
|||
-#endif // !defined(XMEGA_D3) && !defined(LITTLEWIRE) && !defined(RF24_LINUX)
|
|||
-
|
|||
- return true; // assuming pins are connected properly
|
|||
+ return hal->begin();
|
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
@@ -1151,7 +611,7 @@ bool RF24::isChipConnected()
|
|||
|
|||
bool RF24::isValid() |
|||
{ |
|||
- return ce_pin != RF24_PIN_INVALID && csn_pin != RF24_PIN_INVALID;
|
|||
+ return hal != nullptr;
|
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
@@ -1676,15 +1136,8 @@ void RF24::closeReadingPipe(uint8_t pipe)
|
|||
|
|||
void RF24::toggle_features(void) |
|||
{ |
|||
- beginTransaction();
|
|||
-#if defined(RF24_SPI_PTR)
|
|||
- status = _spi->transfer(ACTIVATE);
|
|||
- _spi->transfer(0x73);
|
|||
-#else
|
|||
- status = _SPI.transfer(ACTIVATE);
|
|||
- _SPI.transfer(0x73);
|
|||
-#endif
|
|||
- endTransaction();
|
|||
+ uint8_t value = 0x73;
|
|||
+ status = hal->write(ACTIVATE, &value, sizeof(value));
|
|||
} |
|||
|
|||
/****************************************************************************/ |
|||
diff --git a/RF24.h b/RF24.h
|
|||
index dbd32ae..f774bba 100644
|
|||
--- a/RF24.h
|
|||
+++ b/RF24.h
|
|||
@@ -16,12 +16,7 @@
|
|||
#define __RF24_H__ |
|||
|
|||
#include "RF24_config.h" |
|||
-
|
|||
-#if defined(RF24_LINUX) || defined(LITTLEWIRE)
|
|||
- #include "utility/includes.h"
|
|||
-#elif defined SOFTSPI
|
|||
- #include <DigitalIO.h>
|
|||
-#endif
|
|||
+#include "RF24_hal.h"
|
|||
|
|||
/** |
|||
* @defgroup PALevel Power Amplifier level |
|||
@@ -115,29 +110,8 @@ typedef enum
|
|||
class RF24 |
|||
{ |
|||
private: |
|||
-#ifdef SOFTSPI
|
|||
- SoftSPI<SOFT_SPI_MISO_PIN, SOFT_SPI_MOSI_PIN, SOFT_SPI_SCK_PIN, SPI_MODE> spi;
|
|||
-#elif defined(SPI_UART)
|
|||
- SPIUARTClass uspi;
|
|||
-#endif
|
|||
-
|
|||
-#if defined(RF24_LINUX) || defined(XMEGA_D3) /* XMEGA can use SPI class */
|
|||
- SPI spi;
|
|||
-#endif // defined (RF24_LINUX) || defined (XMEGA_D3)
|
|||
-#if defined(RF24_SPI_PTR)
|
|||
- _SPI* _spi;
|
|||
-#endif // defined (RF24_SPI_PTR)
|
|||
-#if defined(MRAA)
|
|||
- GPIO gpio;
|
|||
-#endif
|
|||
+ RF24_hal *hal;
|
|||
|
|||
- rf24_gpio_pin_t ce_pin; /* "Chip Enable" pin, activates the RX or TX role */
|
|||
- rf24_gpio_pin_t csn_pin; /* SPI Chip select */
|
|||
- uint32_t spi_speed; /* SPI Bus Speed */
|
|||
-#if defined(RF24_LINUX) || defined(XMEGA_D3) || defined(RF24_RP2)
|
|||
- uint8_t spi_rxbuff[32 + 1]; //SPI receive buffer (payload max 32 bytes)
|
|||
- uint8_t spi_txbuff[32 + 1]; //SPI transmit buffer (payload max 32 bytes + 1 byte for the command)
|
|||
-#endif
|
|||
uint8_t status; /* The status byte returned from every SPI transaction */ |
|||
uint8_t payload_size; /* Fixed size of payloads */ |
|||
uint8_t pipe0_reading_address[5]; /* Last address set on pipe 0 for reading. */ |
|||
@@ -146,16 +120,6 @@ private:
|
|||
bool _is_p0_rx; /* For keeping track of pipe 0's usage in user-triggered RX mode. */ |
|||
|
|||
protected: |
|||
- /**
|
|||
- * SPI transactions
|
|||
- *
|
|||
- * Common code for SPI transactions including CSN toggle
|
|||
- *
|
|||
- */
|
|||
- inline void beginTransaction();
|
|||
-
|
|||
- inline void endTransaction();
|
|||
-
|
|||
/** Whether ack payloads are enabled. */ |
|||
bool ack_payloads_enabled; |
|||
/** The address width to use (3, 4 or 5 bytes). */ |
|||
@@ -198,30 +162,15 @@ public:
|
|||
* |
|||
* See [Related Pages](pages.html) for device specific information |
|||
* |
|||
- * @param _cepin The pin attached to Chip Enable on the RF module
|
|||
- * @param _cspin The pin attached to Chip Select (often labeled CSN) on the radio module.
|
|||
- * - For the Arduino Due board, the [Arduino Due extended SPI feature](https://www.arduino.cc/en/Reference/DueExtendedSPI)
|
|||
- * is not supported. This means that the Due's pins 4, 10, or 52 are not mandated options (can use any digital output pin) for
|
|||
- * the radio's CSN pin.
|
|||
- * @param _spi_speed The SPI speed in Hz ie: 1000000 == 1Mhz
|
|||
- * - Users can specify default SPI speed by modifying @ref RF24_SPI_SPEED in @ref RF24_config.h
|
|||
- * - For Arduino, the default SPI speed will only be properly configured this way on devices supporting SPI TRANSACTIONS
|
|||
- * - Older/Unsupported Arduino devices will use a default clock divider & settings configuration
|
|||
- * - For Linux: The old way of setting SPI speeds using BCM2835 driver enums has been removed as of v1.3.7
|
|||
+ * @param _hal A pointer to the device specific hardware abstraction layer
|
|||
*/ |
|||
- RF24(rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin, uint32_t _spi_speed = RF24_SPI_SPEED);
|
|||
+ RF24(RF24_hal *_hal);
|
|||
|
|||
/** |
|||
* A constructor for initializing the radio's hardware dynamically |
|||
- * @warning You MUST use begin(rf24_gpio_pin_t, rf24_gpio_pin_t) or begin(_SPI*, rf24_gpio_pin_t, rf24_gpio_pin_t) to pass both the
|
|||
- * digital output pin numbers connected to the radio's CE and CSN pins.
|
|||
- * @param _spi_speed The SPI speed in Hz ie: 1000000 == 1Mhz
|
|||
- * - Users can specify default SPI speed by modifying @ref RF24_SPI_SPEED in @ref RF24_config.h
|
|||
- * - For Arduino, the default SPI speed will only be properly configured this way on devices supporting SPI TRANSACTIONS
|
|||
- * - Older/Unsupported Arduino devices will use a default clock divider & settings configuration
|
|||
- * - For Linux: The old way of setting SPI speeds using BCM2835 driver enums has been removed as of v1.3.7
|
|||
+ * @warning You MUST use begin(RF24_hal*)
|
|||
*/ |
|||
- RF24(uint32_t _spi_speed = RF24_SPI_SPEED);
|
|||
+ RF24(void);
|
|||
|
|||
#if defined(RF24_LINUX) |
|||
virtual ~RF24() {}; |
|||
@@ -243,58 +192,16 @@ public:
|
|||
*/ |
|||
bool begin(void); |
|||
|
|||
-#if defined(RF24_SPI_PTR) || defined(DOXYGEN_FORCED)
|
|||
/** |
|||
* Same as begin(), but allows specifying a non-default SPI bus to use. |
|||
* |
|||
- * @note This function assumes the `SPI::begin()` method was called before to
|
|||
- * calling this function.
|
|||
- *
|
|||
- * @warning This function is for the Arduino platforms only
|
|||
- *
|
|||
- * @param spiBus A pointer or reference to an instantiated SPI bus object.
|
|||
- * The `_SPI` datatype is a "wrapped" definition that will represent
|
|||
- * various SPI implementations based on the specified platform.
|
|||
- * @see Review the [Arduino support page](md_docs_arduino.html).
|
|||
- *
|
|||
- * @return same result as begin()
|
|||
- */
|
|||
- bool begin(_SPI* spiBus);
|
|||
-
|
|||
- /**
|
|||
- * Same as begin(), but allows dynamically specifying a SPI bus, CE pin,
|
|||
- * and CSN pin to use.
|
|||
- *
|
|||
- * @note This function assumes the `SPI::begin()` method was called before to
|
|||
- * calling this function.
|
|||
- *
|
|||
* @warning This function is for the Arduino platforms only |
|||
* |
|||
- * @param spiBus A pointer or reference to an instantiated SPI bus object.
|
|||
- * The `_SPI` datatype is a "wrapped" definition that will represent
|
|||
- * various SPI implementations based on the specified platform.
|
|||
- * @param _cepin The pin attached to Chip Enable on the RF module
|
|||
- * @param _cspin The pin attached to Chip Select (often labeled CSN) on the radio module.
|
|||
- * - For the Arduino Due board, the [Arduino Due extended SPI feature](https://www.arduino.cc/en/Reference/DueExtendedSPI)
|
|||
- * is not supported. This means that the Due's pins 4, 10, or 52 are not mandated options (can use any digital output pin) for the radio's CSN pin.
|
|||
+ * @param _hal A pointer to the device specific hardware abstraction layer
|
|||
* |
|||
- * @see Review the [Arduino support page](md_docs_arduino.html).
|
|||
- *
|
|||
- * @return same result as begin()
|
|||
- */
|
|||
- bool begin(_SPI* spiBus, rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin);
|
|||
-#endif // defined (RF24_SPI_PTR) || defined (DOXYGEN_FORCED)
|
|||
-
|
|||
- /**
|
|||
- * Same as begin(), but allows dynamically specifying a CE pin
|
|||
- * and CSN pin to use.
|
|||
- * @param _cepin The pin attached to Chip Enable on the RF module
|
|||
- * @param _cspin The pin attached to Chip Select (often labeled CSN) on the radio module.
|
|||
- * - For the Arduino Due board, the [Arduino Due extended SPI feature](https://www.arduino.cc/en/Reference/DueExtendedSPI)
|
|||
- * is not supported. This means that the Due's pins 4, 10, or 52 are not mandated options (can use any digital output pin) for the radio's CSN pin.
|
|||
* @return same result as begin() |
|||
*/ |
|||
- bool begin(rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin);
|
|||
+ bool begin(RF24_hal* _hal);
|
|||
|
|||
/** |
|||
* Checks if the chip is connected to the SPI bus |
|||
@@ -667,12 +574,12 @@ public:
|
|||
* This function uses much less ram than other `*print*Details()` methods. |
|||
* |
|||
* @code |
|||
- * uint8_t encoded_details[43] = {0};
|
|||
+ * uint8_t encoded_details[38] = {0};
|
|||
* radio.encodeRadioDetails(encoded_details); |
|||
* @endcode |
|||
* |
|||
* @param encoded_status The uint8_t array that RF24 radio details are |
|||
- * encoded into. This array must be at least 43 bytes in length; any less would surely
|
|||
+ * encoded into. This array must be at least 38 bytes in length; any less would surely
|
|||
* cause undefined behavior. |
|||
* |
|||
* Registers names and/or data corresponding to the index of the `encoded_details` array: |
|||
@@ -704,9 +611,6 @@ public:
|
|||
* | 35 | FIFO_STATUS | |
|||
* | 36 | DYNPD | |
|||
* | 37 | FEATURE | |
|||
- * | 38-39 | ce_pin |
|
|||
- * | 40-41 | csn_pin |
|
|||
- * | 42 | SPI speed (in MHz) or'd with (isPlusVariant << 4) |
|
|||
*/ |
|||
void encodeRadioDetails(uint8_t* encoded_status); |
|||
|
|||
@@ -1896,18 +1800,6 @@ private:
|
|||
*/ |
|||
bool _init_pins(); |
|||
|
|||
- /**
|
|||
- * Set chip select pin
|
|||
- *
|
|||
- * Running SPI bus at PI_CLOCK_DIV2 so we don't waste time transferring data
|
|||
- * and best of all, we make use of the radio's FIFO buffers. A lower speed
|
|||
- * means we're less likely to effectively leverage our FIFOs and pay a higher
|
|||
- * AVR runtime cost as toll.
|
|||
- *
|
|||
- * @param mode HIGH to take this unit off the SPI bus, LOW to put it on
|
|||
- */
|
|||
- void csn(bool mode);
|
|||
-
|
|||
/** |
|||
* Set chip enable |
|||
* |
|||
diff --git a/RF24_hal.cpp b/RF24_hal.cpp
|
|||
new file mode 100644 |
|||
index 0000000..3cc78e4
|
|||
--- /dev/null
|
|||
+++ b/RF24_hal.cpp
|
|||
@@ -0,0 +1 @@
|
|||
+#include "RF24_hal.h"
|
|||
diff --git a/RF24_hal.h b/RF24_hal.h
|
|||
new file mode 100644 |
|||
index 0000000..baceab3
|
|||
--- /dev/null
|
|||
+++ b/RF24_hal.h
|
|||
@@ -0,0 +1,15 @@
|
|||
+#pragma once
|
|||
+
|
|||
+#include "RF24_config.h"
|
|||
+
|
|||
+class RF24_hal
|
|||
+{
|
|||
+public:
|
|||
+ virtual void ce(bool level) = 0;
|
|||
+ virtual uint8_t read(uint8_t cmd, uint8_t* buf, uint8_t len) = 0;
|
|||
+ virtual uint8_t read(uint8_t cmd, uint8_t* buf, uint8_t data_len, uint8_t blank_len) = 0;
|
|||
+ virtual uint8_t write(uint8_t cmd, const uint8_t* buf, uint8_t len) = 0;
|
|||
+ virtual uint8_t write(uint8_t cmd, const uint8_t* buf, uint8_t len, uint8_t blank_len) = 0;
|
|||
+ virtual bool begin() = 0;
|
|||
+ virtual void end() = 0;
|
|||
+};
|
@ -0,0 +1,141 @@ |
|||
//-----------------------------------------------------------------------------
|
|||
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
|
|||
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
|
|||
//-----------------------------------------------------------------------------
|
|||
|
|||
|
|||
#if defined(CONFIG_IDF_TARGET_ESP32S3) |
|||
#if defined(ETHERNET) |
|||
#ifndef __ETH_SPI_H__ |
|||
#define __ETH_SPI_H__ |
|||
|
|||
#pragma once |
|||
|
|||
#include <Arduino.h> |
|||
#include <esp_netif.h> |
|||
#include <WiFiGeneric.h> |
|||
#include <driver/spi_master.h> |
|||
|
|||
// Functions from WiFiGeneric
|
|||
void tcpipInit(); |
|||
void add_esp_interface_netif(esp_interface_t interface, esp_netif_t* esp_netif); |
|||
|
|||
class EthSpi { |
|||
public: |
|||
|
|||
EthSpi() : |
|||
eth_handle(nullptr), |
|||
eth_netif(nullptr) {} |
|||
|
|||
void begin(int8_t pin_miso, int8_t pin_mosi, int8_t pin_sclk, int8_t pin_cs, int8_t pin_int, int8_t pin_rst) { |
|||
gpio_reset_pin(static_cast<gpio_num_t>(pin_rst)); |
|||
gpio_set_direction(static_cast<gpio_num_t>(pin_rst), GPIO_MODE_OUTPUT); |
|||
gpio_set_level(static_cast<gpio_num_t>(pin_rst), 0); |
|||
|
|||
gpio_reset_pin(static_cast<gpio_num_t>(pin_sclk)); |
|||
gpio_reset_pin(static_cast<gpio_num_t>(pin_mosi)); |
|||
gpio_reset_pin(static_cast<gpio_num_t>(pin_miso)); |
|||
gpio_reset_pin(static_cast<gpio_num_t>(pin_cs)); |
|||
gpio_set_pull_mode(static_cast<gpio_num_t>(pin_miso), GPIO_PULLUP_ONLY); |
|||
|
|||
// Workaround, because calling gpio_install_isr_service directly causes issues with attachInterrupt later
|
|||
attachInterrupt(digitalPinToInterrupt(pin_int), nullptr, CHANGE); |
|||
detachInterrupt(digitalPinToInterrupt(pin_int)); |
|||
gpio_reset_pin(static_cast<gpio_num_t>(pin_int)); |
|||
gpio_set_pull_mode(static_cast<gpio_num_t>(pin_int), GPIO_PULLUP_ONLY); |
|||
|
|||
spi_bus_config_t buscfg = { |
|||
.mosi_io_num = pin_mosi, |
|||
.miso_io_num = pin_miso, |
|||
.sclk_io_num = pin_sclk, |
|||
.quadwp_io_num = -1, |
|||
.quadhd_io_num = -1, |
|||
.data4_io_num = -1, |
|||
.data5_io_num = -1, |
|||
.data6_io_num = -1, |
|||
.data7_io_num = -1, |
|||
.max_transfer_sz = 0, // uses default value internally
|
|||
.flags = 0, |
|||
.intr_flags = 0 |
|||
}; |
|||
|
|||
ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); |
|||
|
|||
spi_device_interface_config_t devcfg = { |
|||
.command_bits = 16, // actually address phase
|
|||
.address_bits = 8, // actually command phase
|
|||
.dummy_bits = 0, |
|||
.mode = 0, |
|||
.duty_cycle_pos = 0, |
|||
.cs_ena_pretrans = 0, // only 0 supported
|
|||
.cs_ena_posttrans = 0, // only 0 supported
|
|||
.clock_speed_hz = 20000000, // stable with on OpenDTU Fusion Shield
|
|||
.input_delay_ns = 0, |
|||
.spics_io_num = pin_cs, |
|||
.flags = 0, |
|||
.queue_size = 20, |
|||
.pre_cb = nullptr, |
|||
.post_cb = nullptr |
|||
}; |
|||
|
|||
spi_device_handle_t spi; |
|||
ESP_ERROR_CHECK(spi_bus_add_device(SPI3_HOST, &devcfg, &spi)); |
|||
|
|||
// Reset sequence
|
|||
delayMicroseconds(500); |
|||
gpio_set_level(static_cast<gpio_num_t>(pin_rst), 1); |
|||
delayMicroseconds(1000); |
|||
|
|||
// Arduino function to start networking stack if not already started
|
|||
tcpipInit(); |
|||
|
|||
ESP_ERROR_CHECK(tcpip_adapter_set_default_eth_handlers()); // ?
|
|||
|
|||
eth_w5500_config_t w5500_config = ETH_W5500_DEFAULT_CONFIG(spi); |
|||
w5500_config.int_gpio_num = pin_int; |
|||
|
|||
eth_mac_config_t mac_config = ETH_MAC_DEFAULT_CONFIG(); |
|||
mac_config.rx_task_stack_size = 4096; |
|||
esp_eth_mac_t *mac = esp_eth_mac_new_w5500(&w5500_config, &mac_config); |
|||
|
|||
eth_phy_config_t phy_config = ETH_PHY_DEFAULT_CONFIG(); |
|||
phy_config.reset_gpio_num = -1; |
|||
esp_eth_phy_t *phy = esp_eth_phy_new_w5500(&phy_config); |
|||
|
|||
esp_eth_config_t eth_config = ETH_DEFAULT_CONFIG(mac, phy); |
|||
ESP_ERROR_CHECK(esp_eth_driver_install(ð_config, ð_handle)); |
|||
|
|||
// Configure MAC address
|
|||
uint8_t mac_addr[6]; |
|||
ESP_ERROR_CHECK(esp_efuse_mac_get_default(mac_addr)); |
|||
mac_addr[5] |= 0x03; // derive ethernet MAC address from base MAC address
|
|||
ESP_ERROR_CHECK(esp_eth_ioctl(eth_handle, ETH_CMD_S_MAC_ADDR, mac_addr)); |
|||
|
|||
esp_netif_config_t netif_config = ESP_NETIF_DEFAULT_ETH(); |
|||
eth_netif = esp_netif_new(&netif_config); |
|||
|
|||
ESP_ERROR_CHECK(esp_netif_attach(eth_netif, esp_eth_new_netif_glue(eth_handle))); |
|||
|
|||
// Add to Arduino
|
|||
add_esp_interface_netif(ESP_IF_ETH, eth_netif); |
|||
|
|||
ESP_ERROR_CHECK(esp_eth_start(eth_handle)); |
|||
} |
|||
|
|||
String macAddress() { |
|||
uint8_t mac_addr[6] = {0, 0, 0, 0, 0, 0}; |
|||
esp_eth_ioctl(eth_handle, ETH_CMD_G_MAC_ADDR, mac_addr); |
|||
char mac_addr_str[24]; |
|||
snprintf(mac_addr_str, sizeof(mac_addr_str), "%02X:%02X:%02X:%02X:%02X:%02X", mac_addr[0], mac_addr[1], mac_addr[2], mac_addr[3], mac_addr[4], mac_addr[5]); |
|||
return String(mac_addr_str); |
|||
} |
|||
|
|||
|
|||
private: |
|||
esp_eth_handle_t eth_handle; |
|||
esp_netif_t *eth_netif; |
|||
}; |
|||
|
|||
#endif /*__ETH_SPI_H__*/ |
|||
#endif /*ETHERNET*/ |
|||
#endif /*CONFIG_IDF_TARGET_ESP32S3*/ |
@ -0,0 +1,32 @@ |
|||
//-----------------------------------------------------------------------------
|
|||
// 2023 Ahoy, https://github.com/lumpapu/ahoy
|
|||
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/4.0/deed
|
|||
//-----------------------------------------------------------------------------
|
|||
|
|||
#ifndef __HEURISTIC_INV_H__ |
|||
#define __HEURISTIC_INV_H__ |
|||
|
|||
#define RF_MAX_CHANNEL_ID 5 |
|||
#define RF_MAX_QUALITY 4 |
|||
#define RF_MIN_QUALTIY -6 |
|||
#define RF_NA -99 |
|||
|
|||
class HeuristicInv { |
|||
public: |
|||
HeuristicInv() { |
|||
memset(txRfQuality, -6, RF_MAX_CHANNEL_ID); |
|||
} |
|||
|
|||
public: |
|||
int8_t txRfQuality[RF_MAX_CHANNEL_ID]; // heuristics tx quality (check 'Heuristics.h')
|
|||
uint8_t txRfChId = 0; // RF TX channel id
|
|||
uint8_t lastBestTxChId = 0; |
|||
|
|||
uint8_t testPeriodSendCnt = 0; |
|||
uint8_t testPeriodFailCnt = 0; |
|||
uint8_t testChId = 0; |
|||
int8_t saveOldTestQuality = -6; |
|||
uint8_t lastRxFragments = 0; |
|||
}; |
|||
|
|||
#endif /*__HEURISTIC_INV_H__*/ |
@ -0,0 +1,218 @@ |
|||
//-----------------------------------------------------------------------------
|
|||
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
|
|||
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
|
|||
//-----------------------------------------------------------------------------
|
|||
|
|||
#ifndef __NRF_HAL_H__ |
|||
#define __NRF_HAL_H__ |
|||
|
|||
#pragma once |
|||
|
|||
#include "../utils/spiPatcher.h" |
|||
|
|||
#include <esp_rom_gpio.h> |
|||
#include <RF24_hal.h> |
|||
|
|||
#define NRF_MAX_TRANSFER_SZ 64 |
|||
#define NRF_DEFAULT_SPI_SPEED 10000000 // 10 MHz
|
|||
|
|||
class nrfHal: public RF24_hal, public SpiPatcherHandle { |
|||
public: |
|||
nrfHal() { |
|||
mSpiPatcher = SpiPatcher::getInstance(SPI2_HOST); |
|||
} |
|||
|
|||
void patch() override { |
|||
esp_rom_gpio_connect_out_signal(mPinMosi, spi_periph_signal[mHostDevice].spid_out, false, false); |
|||
esp_rom_gpio_connect_in_signal(mPinMiso, spi_periph_signal[mHostDevice].spiq_in, false); |
|||
esp_rom_gpio_connect_out_signal(mPinClk, spi_periph_signal[mHostDevice].spiclk_out, false, false); |
|||
} |
|||
|
|||
void unpatch() override { |
|||
esp_rom_gpio_connect_out_signal(mPinMosi, SIG_GPIO_OUT_IDX, false, false); |
|||
esp_rom_gpio_connect_in_signal(mPinMiso, GPIO_MATRIX_CONST_ZERO_INPUT, false); |
|||
esp_rom_gpio_connect_out_signal(mPinClk, SIG_GPIO_OUT_IDX, false, false); |
|||
} |
|||
|
|||
void init(int8_t mosi, int8_t miso, int8_t sclk, int8_t cs, int8_t en, int32_t speed = NRF_DEFAULT_SPI_SPEED) { |
|||
mPinMosi = static_cast<gpio_num_t>(mosi); |
|||
mPinMiso = static_cast<gpio_num_t>(miso); |
|||
mPinClk = static_cast<gpio_num_t>(sclk); |
|||
mPinCs = static_cast<gpio_num_t>(cs); |
|||
mPinEn = static_cast<gpio_num_t>(en); |
|||
mSpiSpeed = speed; |
|||
|
|||
mHostDevice = mSpiPatcher->getDevice(); |
|||
|
|||
gpio_reset_pin(mPinMosi); |
|||
gpio_set_direction(mPinMosi, GPIO_MODE_OUTPUT); |
|||
gpio_set_level(mPinMosi, 1); |
|||
|
|||
gpio_reset_pin(mPinMiso); |
|||
gpio_set_direction(mPinMiso, GPIO_MODE_INPUT); |
|||
|
|||
gpio_reset_pin(mPinClk); |
|||
gpio_set_direction(mPinClk, GPIO_MODE_OUTPUT); |
|||
gpio_set_level(mPinClk, 0); |
|||
|
|||
gpio_reset_pin(mPinCs); |
|||
spi_device_interface_config_t devcfg = { |
|||
.command_bits = 0, |
|||
.address_bits = 0, |
|||
.dummy_bits = 0, |
|||
.mode = 0, |
|||
.duty_cycle_pos = 0, |
|||
.cs_ena_pretrans = 0, |
|||
.cs_ena_posttrans = 0, |
|||
.clock_speed_hz = mSpiSpeed, |
|||
.input_delay_ns = 0, |
|||
.spics_io_num = mPinCs, |
|||
.flags = 0, |
|||
.queue_size = 1, |
|||
.pre_cb = nullptr, |
|||
.post_cb = nullptr |
|||
}; |
|||
ESP_ERROR_CHECK(spi_bus_add_device(mHostDevice, &devcfg, &spi)); |
|||
|
|||
gpio_reset_pin(mPinEn); |
|||
gpio_set_direction(mPinEn, GPIO_MODE_OUTPUT); |
|||
gpio_set_level(mPinEn, 0); |
|||
} |
|||
|
|||
|
|||
bool begin() override { |
|||
return true; |
|||
} |
|||
|
|||
void end() override {} |
|||
|
|||
void ce(bool level) override { |
|||
gpio_set_level(mPinEn, level); |
|||
} |
|||
|
|||
uint8_t write(uint8_t cmd, const uint8_t* buf, uint8_t len) override { |
|||
uint8_t data[NRF_MAX_TRANSFER_SZ]; |
|||
data[0] = cmd; |
|||
std::copy(&buf[0], &buf[len], &data[1]); |
|||
|
|||
request_spi(); |
|||
|
|||
size_t spiLen = (static_cast<size_t>(len) + 1u) << 3; |
|||
spi_transaction_t t = { |
|||
.flags = 0, |
|||
.cmd = 0, |
|||
.addr = 0, |
|||
.length = spiLen, |
|||
.rxlength = spiLen, |
|||
.user = NULL, |
|||
.tx_buffer = data, |
|||
.rx_buffer = data |
|||
}; |
|||
ESP_ERROR_CHECK(spi_device_polling_transmit(spi, &t)); |
|||
|
|||
release_spi(); |
|||
|
|||
return data[0]; // status
|
|||
} |
|||
|
|||
uint8_t write(uint8_t cmd, const uint8_t* buf, uint8_t data_len, uint8_t blank_len) override { |
|||
uint8_t data[NRF_MAX_TRANSFER_SZ]; |
|||
data[0] = cmd; |
|||
memset(data, 0, NRF_MAX_TRANSFER_SZ); |
|||
std::copy(&buf[0], &buf[data_len], &data[1]); |
|||
|
|||
request_spi(); |
|||
|
|||
size_t spiLen = (static_cast<size_t>(data_len) + static_cast<size_t>(blank_len) + 1u) << 3; |
|||
spi_transaction_t t = { |
|||
.flags = 0, |
|||
.cmd = 0, |
|||
.addr = 0, |
|||
.length = spiLen, |
|||
.rxlength = spiLen, |
|||
.user = NULL, |
|||
.tx_buffer = data, |
|||
.rx_buffer = data |
|||
}; |
|||
ESP_ERROR_CHECK(spi_device_polling_transmit(spi, &t)); |
|||
|
|||
release_spi(); |
|||
|
|||
return data[0]; // status
|
|||
} |
|||
|
|||
uint8_t read(uint8_t cmd, uint8_t* buf, uint8_t len) override { |
|||
uint8_t data[NRF_MAX_TRANSFER_SZ]; |
|||
data[0] = cmd; |
|||
memset(&data[1], 0xff, len); |
|||
|
|||
request_spi(); |
|||
|
|||
size_t spiLen = (static_cast<size_t>(len) + 1u) << 3; |
|||
spi_transaction_t t = { |
|||
.flags = 0, |
|||
.cmd = 0, |
|||
.addr = 0, |
|||
.length = spiLen, |
|||
.rxlength = spiLen, |
|||
.user = NULL, |
|||
.tx_buffer = data, |
|||
.rx_buffer = data |
|||
}; |
|||
ESP_ERROR_CHECK(spi_device_polling_transmit(spi, &t)); |
|||
|
|||
release_spi(); |
|||
|
|||
std::copy(&data[1], &data[len+1], buf); |
|||
return data[0]; // status
|
|||
} |
|||
|
|||
uint8_t read(uint8_t cmd, uint8_t* buf, uint8_t data_len, uint8_t blank_len) override { |
|||
uint8_t data[NRF_MAX_TRANSFER_SZ]; |
|||
data[0] = cmd; |
|||
memset(&data[1], 0xff, (data_len + blank_len)); |
|||
|
|||
request_spi(); |
|||
|
|||
size_t spiLen = (static_cast<size_t>(data_len) + static_cast<size_t>(blank_len) + 1u) << 3; |
|||
spi_transaction_t t = { |
|||
.flags = 0, |
|||
.cmd = 0, |
|||
.addr = 0, |
|||
.length = spiLen, |
|||
.rxlength = spiLen, |
|||
.user = NULL, |
|||
.tx_buffer = data, |
|||
.rx_buffer = data |
|||
}; |
|||
ESP_ERROR_CHECK(spi_device_polling_transmit(spi, &t)); |
|||
|
|||
release_spi(); |
|||
|
|||
std::copy(&data[1], &data[data_len+1], buf); |
|||
return data[0]; // status
|
|||
} |
|||
|
|||
private: |
|||
inline void request_spi() { |
|||
mSpiPatcher->request(this); |
|||
} |
|||
|
|||
inline void release_spi() { |
|||
mSpiPatcher->release(); |
|||
} |
|||
|
|||
private: |
|||
gpio_num_t mPinMosi = GPIO_NUM_NC; |
|||
gpio_num_t mPinMiso = GPIO_NUM_NC; |
|||
gpio_num_t mPinClk = GPIO_NUM_NC; |
|||
gpio_num_t mPinCs = GPIO_NUM_NC; |
|||
gpio_num_t mPinEn = GPIO_NUM_NC; |
|||
int32_t mSpiSpeed = NRF_DEFAULT_SPI_SPEED; |
|||
|
|||
spi_host_device_t mHostDevice; |
|||
spi_device_handle_t spi; |
|||
SpiPatcher *mSpiPatcher; |
|||
}; |
|||
|
|||
#endif /*__NRF_HAL_H__*/ |
@ -0,0 +1,196 @@ |
|||
//-----------------------------------------------------------------------------
|
|||
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
|
|||
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
|
|||
//-----------------------------------------------------------------------------
|
|||
|
|||
#ifndef __CMT_HAL_H__ |
|||
#define __CMT_HAL_H__ |
|||
|
|||
#pragma once |
|||
|
|||
#include "../utils/spiPatcher.h" |
|||
|
|||
#include <driver/gpio.h> |
|||
|
|||
#define CMT_DEFAULT_SPI_SPEED 4000000 // 4 MHz
|
|||
|
|||
class cmtHal : public SpiPatcherHandle { |
|||
public: |
|||
cmtHal() { |
|||
mSpiPatcher = SpiPatcher::getInstance(SPI2_HOST); |
|||
} |
|||
|
|||
void patch() override { |
|||
esp_rom_gpio_connect_out_signal(mPinSdio, spi_periph_signal[mHostDevice].spid_out, false, false); |
|||
esp_rom_gpio_connect_in_signal(mPinSdio, spi_periph_signal[mHostDevice].spid_in, false); |
|||
esp_rom_gpio_connect_out_signal(mPinClk, spi_periph_signal[mHostDevice].spiclk_out, false, false); |
|||
} |
|||
|
|||
void unpatch() override { |
|||
esp_rom_gpio_connect_out_signal(mPinSdio, SIG_GPIO_OUT_IDX, false, false); |
|||
esp_rom_gpio_connect_in_signal(mPinSdio, GPIO_MATRIX_CONST_ZERO_INPUT, false); |
|||
esp_rom_gpio_connect_out_signal(mPinClk, SIG_GPIO_OUT_IDX, false, false); |
|||
} |
|||
|
|||
void init(int8_t sdio, int8_t clk, int8_t cs, int8_t fcs, int32_t speed = CMT_DEFAULT_SPI_SPEED) { |
|||
mPinSdio = static_cast<gpio_num_t>(sdio); |
|||
mPinClk = static_cast<gpio_num_t>(clk); |
|||
mPinCs = static_cast<gpio_num_t>(cs); |
|||
mPinFcs = static_cast<gpio_num_t>(fcs); |
|||
mSpiSpeed = speed; |
|||
|
|||
mHostDevice = mSpiPatcher->getDevice(); |
|||
|
|||
gpio_reset_pin(mPinSdio); |
|||
gpio_set_direction(mPinSdio, GPIO_MODE_INPUT_OUTPUT); |
|||
gpio_set_level(mPinSdio, 1); |
|||
|
|||
gpio_reset_pin(mPinClk); |
|||
gpio_set_direction(mPinClk, GPIO_MODE_OUTPUT); |
|||
gpio_set_level(mPinClk, 0); |
|||
|
|||
gpio_reset_pin(mPinCs); |
|||
spi_device_interface_config_t devcfg_reg = { |
|||
.command_bits = 1, |
|||
.address_bits = 7, |
|||
.dummy_bits = 0, |
|||
.mode = 0, |
|||
.duty_cycle_pos = 0, |
|||
.cs_ena_pretrans = 1, |
|||
.cs_ena_posttrans = 1, |
|||
.clock_speed_hz = mSpiSpeed, |
|||
.input_delay_ns = 0, |
|||
.spics_io_num = mPinCs, |
|||
.flags = SPI_DEVICE_HALFDUPLEX | SPI_DEVICE_3WIRE, |
|||
.queue_size = 1, |
|||
.pre_cb = nullptr, |
|||
.post_cb = nullptr |
|||
}; |
|||
ESP_ERROR_CHECK(spi_bus_add_device(mHostDevice, &devcfg_reg, &spi_reg)); |
|||
|
|||
gpio_reset_pin(mPinFcs); |
|||
spi_device_interface_config_t devcfg_fifo = { |
|||
.command_bits = 0, |
|||
.address_bits = 0, |
|||
.dummy_bits = 0, |
|||
.mode = 0, |
|||
.duty_cycle_pos = 0, |
|||
.cs_ena_pretrans = 2, |
|||
.cs_ena_posttrans = static_cast<uint8_t>(2 * mSpiSpeed / 1000000), // >2 us
|
|||
.clock_speed_hz = mSpiSpeed, |
|||
.input_delay_ns = 0, |
|||
.spics_io_num = mPinFcs, |
|||
.flags = SPI_DEVICE_HALFDUPLEX | SPI_DEVICE_3WIRE, |
|||
.queue_size = 1, |
|||
.pre_cb = nullptr, |
|||
.post_cb = nullptr |
|||
}; |
|||
ESP_ERROR_CHECK(spi_bus_add_device(mHostDevice, &devcfg_fifo, &spi_fifo)); |
|||
} |
|||
|
|||
uint8_t readReg(uint8_t addr) { |
|||
uint8_t data; |
|||
|
|||
request_spi(); |
|||
|
|||
spi_transaction_t t = { |
|||
.flags = 0, |
|||
.cmd = 1, |
|||
.addr = addr, |
|||
.length = 0, |
|||
.rxlength = 8, |
|||
.user = NULL, |
|||
.tx_buffer = NULL, |
|||
.rx_buffer = &data |
|||
}; |
|||
ESP_ERROR_CHECK(spi_device_polling_transmit(spi_reg, &t)); |
|||
|
|||
release_spi(); |
|||
|
|||
return data; |
|||
} |
|||
|
|||
void writeReg(uint8_t addr, uint8_t data) { |
|||
request_spi(); |
|||
|
|||
spi_transaction_t t = { |
|||
.flags = 0, |
|||
.cmd = 0, |
|||
.addr = addr, |
|||
.length = 8, |
|||
.rxlength = 0, |
|||
.user = NULL, |
|||
.tx_buffer = &data, |
|||
.rx_buffer = NULL |
|||
}; |
|||
ESP_ERROR_CHECK(spi_device_polling_transmit(spi_reg, &t)); |
|||
|
|||
release_spi(); |
|||
} |
|||
|
|||
void readFifo(uint8_t buf[], uint8_t *len, uint8_t maxlen) { |
|||
request_spi(); |
|||
|
|||
spi_transaction_t t = { |
|||
.flags = 0, |
|||
.cmd = 0, |
|||
.addr = 0, |
|||
.length = 0, |
|||
.rxlength = 8, |
|||
.user = NULL, |
|||
.tx_buffer = NULL, |
|||
.rx_buffer = NULL |
|||
}; |
|||
for (uint8_t i = 0; i < maxlen; i++) { |
|||
if(0 == i) |
|||
t.rx_buffer = len; |
|||
else |
|||
t.rx_buffer = buf + i - 1; |
|||
ESP_ERROR_CHECK(spi_device_polling_transmit(spi_fifo, &t)); |
|||
} |
|||
|
|||
release_spi(); |
|||
} |
|||
void writeFifo(const uint8_t buf[], uint16_t len) { |
|||
request_spi(); |
|||
|
|||
spi_transaction_t t = { |
|||
.flags = 0, |
|||
.cmd = 0, |
|||
.addr = 0, |
|||
.length = 8, |
|||
.rxlength = 0, |
|||
.user = NULL, |
|||
.tx_buffer = NULL, |
|||
.rx_buffer = NULL |
|||
}; |
|||
for (uint16_t i = 0; i < len; i++) { |
|||
t.tx_buffer = buf + i; |
|||
ESP_ERROR_CHECK(spi_device_polling_transmit(spi_fifo, &t)); |
|||
} |
|||
|
|||
release_spi(); |
|||
} |
|||
|
|||
private: |
|||
inline void request_spi() { |
|||
mSpiPatcher->request(this); |
|||
} |
|||
|
|||
inline void release_spi() { |
|||
mSpiPatcher->release(); |
|||
} |
|||
|
|||
private: |
|||
gpio_num_t mPinSdio = GPIO_NUM_NC; |
|||
gpio_num_t mPinClk = GPIO_NUM_NC; |
|||
gpio_num_t mPinCs = GPIO_NUM_NC; |
|||
gpio_num_t mPinFcs = GPIO_NUM_NC; |
|||
int32_t mSpiSpeed = CMT_DEFAULT_SPI_SPEED; |
|||
|
|||
spi_host_device_t mHostDevice; |
|||
spi_device_handle_t spi_reg, spi_fifo; |
|||
SpiPatcher *mSpiPatcher; |
|||
}; |
|||
|
|||
#endif /*__CMT_HAL_H__*/ |
@ -0,0 +1,9 @@ |
|||
//-----------------------------------------------------------------------------
|
|||
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
|
|||
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
|
|||
//-----------------------------------------------------------------------------
|
|||
|
|||
#if defined(ESP32) |
|||
#include "spiPatcher.h" |
|||
SpiPatcher *SpiPatcher::mInstance = nullptr; |
|||
#endif |
@ -0,0 +1,88 @@ |
|||
//-----------------------------------------------------------------------------
|
|||
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
|
|||
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
|
|||
//-----------------------------------------------------------------------------
|
|||
|
|||
#ifndef __SPI_PATCHER_H__ |
|||
#define __SPI_PATCHER_H__ |
|||
#pragma once |
|||
|
|||
#if defined(ESP32) |
|||
|
|||
#include "spiPatcherHandle.h" |
|||
|
|||
#include <driver/spi_master.h> |
|||
#include <freertos/semphr.h> |
|||
|
|||
class SpiPatcher { |
|||
protected: |
|||
SpiPatcher(spi_host_device_t dev) : |
|||
mHostDevice(dev), mCurHandle(nullptr) { |
|||
// Use binary semaphore instead of mutex for performance reasons
|
|||
mutex = xSemaphoreCreateBinaryStatic(&mutex_buffer); |
|||
xSemaphoreGive(mutex); |
|||
|
|||
spi_bus_config_t buscfg = { |
|||
.mosi_io_num = -1, |
|||
.miso_io_num = -1, |
|||
.sclk_io_num = -1, |
|||
.quadwp_io_num = -1, |
|||
.quadhd_io_num = -1, |
|||
.data4_io_num = -1, |
|||
.data5_io_num = -1, |
|||
.data6_io_num = -1, |
|||
.data7_io_num = -1, |
|||
.max_transfer_sz = SOC_SPI_MAXIMUM_BUFFER_SIZE, |
|||
.flags = 0, |
|||
.intr_flags = 0 |
|||
}; |
|||
ESP_ERROR_CHECK(spi_bus_initialize(mHostDevice, &buscfg, SPI_DMA_DISABLED)); |
|||
} |
|||
|
|||
public: |
|||
SpiPatcher(SpiPatcher &other) = delete; |
|||
void operator=(const SpiPatcher &) = delete; |
|||
|
|||
static SpiPatcher* getInstance(spi_host_device_t dev) { |
|||
if(nullptr == mInstance) |
|||
mInstance = new SpiPatcher(dev); |
|||
return mInstance; |
|||
} |
|||
|
|||
~SpiPatcher() { vSemaphoreDelete(mutex); } |
|||
|
|||
spi_host_device_t getDevice() { |
|||
return mHostDevice; |
|||
} |
|||
|
|||
inline void request(SpiPatcherHandle* handle) { |
|||
xSemaphoreTake(mutex, portMAX_DELAY); |
|||
|
|||
if (mCurHandle != handle) { |
|||
if (mCurHandle) { |
|||
mCurHandle->unpatch(); |
|||
} |
|||
mCurHandle = handle; |
|||
if (mCurHandle) { |
|||
mCurHandle->patch(); |
|||
} |
|||
} |
|||
} |
|||
|
|||
inline void release() { |
|||
xSemaphoreGive(mutex); |
|||
} |
|||
|
|||
protected: |
|||
static SpiPatcher *mInstance; |
|||
|
|||
private: |
|||
const spi_host_device_t mHostDevice; |
|||
SpiPatcherHandle* mCurHandle; |
|||
SemaphoreHandle_t mutex; |
|||
StaticSemaphore_t mutex_buffer; |
|||
}; |
|||
|
|||
#endif /*ESP32*/ |
|||
|
|||
#endif /*__SPI_PATCHER_H__*/ |
@ -0,0 +1,17 @@ |
|||
//-----------------------------------------------------------------------------
|
|||
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
|
|||
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
|
|||
//-----------------------------------------------------------------------------
|
|||
|
|||
#ifndef __SPI_PATCHER_HANDLE_H__ |
|||
#define __SPI_PATCHER_HANDLE_H__ |
|||
#pragma once |
|||
|
|||
class SpiPatcherHandle { |
|||
public: |
|||
virtual ~SpiPatcherHandle() {} |
|||
virtual void patch() = 0; |
|||
virtual void unpatch() = 0; |
|||
}; |
|||
|
|||
#endif /*__SPI_PATCHER_HANDLE_H__*/ |
Binary file not shown.
Binary file not shown.
Loading…
Reference in new issue