From aa1dbcea6b9c9be6f447b522489ab9efbf47801b Mon Sep 17 00:00:00 2001 From: Alberto Nidasio <alberto.nidasio@skywarder.eu> Date: Wed, 15 Mar 2023 09:31:13 +0100 Subject: [PATCH] [sx1278] Updated SPI implementation --- .vscode/settings.json | 3 +- src/entrypoints/sx1278-serial.cpp | 4 +- src/shared/radio/SX1278/SX1278Fsk.cpp | 44 +++++++++---------- src/shared/radio/SX1278/SX1278Lora.cpp | 24 +++++----- .../sx1278/fsk/test-sx1278-bench-gui.cpp | 4 +- .../sx1278/fsk/test-sx1278-bench-serial.cpp | 4 +- .../radio/sx1278/fsk/test-sx1278-bidir.cpp | 4 +- .../radio/sx1278/fsk/test-sx1278-mavlink.cpp | 4 +- .../radio/sx1278/lora/test-sx1278-bidir.cpp | 4 +- .../radio/sx1278/lora/test-sx1278-mavlink.cpp | 4 +- .../radio/sx1278/lora/test-sx1278-simple.cpp | 4 +- 11 files changed, 59 insertions(+), 44 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index fc1ab461a..68d8988bc 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -150,7 +150,6 @@ "cwise", "cyaw", "DATABUS", - "datasheet", "deleteme", "DMEIE", "Doxyfile", @@ -304,4 +303,4 @@ ], "cSpell.language": "en", "cSpell.enabled": true -} \ No newline at end of file +} diff --git a/src/entrypoints/sx1278-serial.cpp b/src/entrypoints/sx1278-serial.cpp index dc437055a..72fdc096e 100644 --- a/src/entrypoints/sx1278-serial.cpp +++ b/src/entrypoints/sx1278-serial.cpp @@ -163,7 +163,9 @@ int main() SPIBusConfig spi_config; spi_config.clockDivider = SPI::ClockDivider::DIV_64; spi_config.mode = SPI::Mode::MODE_0; - spi_config.bitOrder = SPI::BitOrder::MSB_FIRST; + spi_config.bitOrder = SPI::Order::MSB_FIRST; + spi_config.byteOrder = SPI::Order::MSB_FIRST; + spi_config.writeBit = SPI::WriteBit::INVERTED; SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp index d67100699..dcf556af7 100644 --- a/src/shared/radio/SX1278/SX1278Fsk.cpp +++ b/src/shared/radio/SX1278/SX1278Fsk.cpp @@ -71,7 +71,7 @@ SX1278Fsk::Error SX1278Fsk::init(const Config &config) bool SX1278Fsk::checkVersion() { Lock guard(*this); - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); return spi.readRegister(REG_VERSION) == 0x12; } @@ -108,7 +108,7 @@ SX1278Fsk::Error SX1278Fsk::configure(const Config &config) // Setup generic parameters { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_RX_CONFIG, RegRxConfig::AFC_AUTO_ON | RegRxConfig::AGC_AUTO_ON | @@ -155,7 +155,7 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len) last_rx_rssi = getRssi(); { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); len = spi.readRegister(REG_FIFO); if (len > max_len) return -1; @@ -186,7 +186,7 @@ bool SX1278Fsk::send(uint8_t *pkt, size_t len) waitForIrq(guard_mode, RegIrqFlags::TX_READY); { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_FIFO, static_cast<uint8_t>(len)); spi.writeRegisters(REG_FIFO, pkt, len); @@ -226,7 +226,7 @@ void SX1278Fsk::rateLimitTx() void SX1278Fsk::imageCalibrate() { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_IMAGE_CAL, REG_IMAGE_CAL_DEFAULT | (1 << 6)); // Wait for calibration complete by polling on running register @@ -262,7 +262,7 @@ DioMask SX1278Fsk::getDioMaskFromIrqFlags(IrqFlags flags, Mode mode, ISX1278::IrqFlags SX1278Fsk::getIrqFlags() { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); uint8_t flags_msb = spi.readRegister(REG_IRQ_FLAGS_1); uint8_t flags_lsb = spi.readRegister(REG_IRQ_FLAGS_2); @@ -279,7 +279,7 @@ void SX1278Fsk::resetIrqFlags(IrqFlags flags) if (flags != 0) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_IRQ_FLAGS_1, flags >> 8); spi.writeRegister(REG_IRQ_FLAGS_2, flags); } @@ -287,14 +287,14 @@ void SX1278Fsk::resetIrqFlags(IrqFlags flags) float SX1278Fsk::getRssi() { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); return static_cast<float>(spi.readRegister(REG_RSSI_VALUE)) * -0.5f; } float SX1278Fsk::getFei() { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); // Order of read is important!! uint8_t fei_msb = spi.readRegister(REG_FEI_MSB); @@ -308,13 +308,13 @@ float SX1278Fsk::getFei() void SX1278Fsk::setMode(Mode mode) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_OP_MODE, REG_OP_MODE_DEFAULT | mode); } void SX1278Fsk::setMapping(SX1278::DioMapping mapping) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_DIO_MAPPING_1, mapping.raw >> 8); spi.writeRegister(REG_DIO_MAPPING_2, mapping.raw); } @@ -324,7 +324,7 @@ void SX1278Fsk::setBitrate(int bitrate) uint16_t val = FXOSC / bitrate; // Update values - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_BITRATE_MSB, val >> 8); spi.writeRegister(REG_BITRATE_LSB, val); } @@ -332,7 +332,7 @@ void SX1278Fsk::setBitrate(int bitrate) void SX1278Fsk::setFreqDev(int freq_dev) { uint16_t val = freq_dev / FSTEP; - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_FDEV_MSB, (val >> 8) & 0x3f); spi.writeRegister(REG_FDEV_LSB, val); } @@ -342,7 +342,7 @@ void SX1278Fsk::setFreqRF(int freq_rf) uint32_t val = freq_rf / FSTEP; // Update values - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_FRF_MSB, val >> 16); spi.writeRegister(REG_FRF_MID, val >> 8); spi.writeRegister(REG_FRF_LSB, val); @@ -350,7 +350,7 @@ void SX1278Fsk::setFreqRF(int freq_rf) void SX1278Fsk::setOcp(int ocp) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); if (ocp == 0) { spi.writeRegister(REG_OCP, 0); @@ -369,7 +369,7 @@ void SX1278Fsk::setOcp(int ocp) void SX1278Fsk::setSyncWord(uint8_t value[], int size) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_SYNC_CONFIG, REG_SYNC_CONFIG_DEFAULT | size); for (int i = 0; i < size; i++) @@ -380,19 +380,19 @@ void SX1278Fsk::setSyncWord(uint8_t value[], int size) void SX1278Fsk::setRxBw(RxBw rx_bw) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_RX_BW, static_cast<uint8_t>(rx_bw)); } void SX1278Fsk::setAfcBw(RxBw afc_bw) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_AFC_BW, static_cast<uint8_t>(afc_bw)); } void SX1278Fsk::setPreambleLen(int len) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_PREAMBLE_MSB, len >> 8); spi.writeRegister(REG_PREAMBLE_LSB, len); } @@ -404,7 +404,7 @@ void SX1278Fsk::setPa(int power, bool pa_boost) const uint8_t MAX_POWER = 0b111; - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); if (!pa_boost) { @@ -435,7 +435,7 @@ void SX1278Fsk::setPa(int power, bool pa_boost) void SX1278Fsk::setShaping(Shaping shaping) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_PA_RAMP, static_cast<uint8_t>(shaping) | 0x09); } @@ -505,7 +505,7 @@ void SX1278Fsk::debugDumpRegisters() RegDef{"REG_DIO_MAPPING_2", REG_DIO_MAPPING_2}, RegDef{"REG_VERSION", REG_VERSION}, RegDef{NULL, 0}}; - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); int i = 0; while (defs[i].name) diff --git a/src/shared/radio/SX1278/SX1278Lora.cpp b/src/shared/radio/SX1278/SX1278Lora.cpp index de35bc5a1..08162a5ac 100644 --- a/src/shared/radio/SX1278/SX1278Lora.cpp +++ b/src/shared/radio/SX1278/SX1278Lora.cpp @@ -149,7 +149,7 @@ SX1278Lora::Error SX1278Lora::init(const Config &config) bool SX1278Lora::checkVersion() { Lock guard(*this); - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); return spi.readRegister(REG_VERSION) == 0x12; } @@ -188,7 +188,7 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config) ErrataRegistersValues::calculate(bw, freq_rf); { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); // Setup FIFO sections spi.writeRegister(REG_FIFO_TX_BASE_ADDR, FIFO_TX_BASE_ADDR); @@ -277,7 +277,7 @@ ssize_t SX1278Lora::receive(uint8_t *pkt, size_t max_len) { Lock guard(*this); - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); do { @@ -305,7 +305,7 @@ bool SX1278Lora::send(uint8_t *pkt, size_t len) Lock guard(*this); - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_PAYLOAD_LENGTH, len); writeFifo(FIFO_TX_BASE_ADDR, pkt, len); @@ -327,7 +327,7 @@ float SX1278Lora::getLastRxRssi() float rssi; { Lock guard(*this); - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); rssi = static_cast<float>(spi.readRegister(REG_PKT_RSSI_VALUE)) - 164.0f; } @@ -343,7 +343,7 @@ float SX1278Lora::getLastRxRssi() float SX1278Lora::getLastRxSnr() { Lock guard(*this); - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); return static_cast<float>( static_cast<int8_t>(spi.readRegister(REG_PKT_SNR_VALUE))) / 4.0f; @@ -351,14 +351,14 @@ float SX1278Lora::getLastRxSnr() void SX1278Lora::readFifo(uint8_t addr, uint8_t *dst, uint8_t size) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_FIFO_ADDR_PTR, addr); spi.readRegisters(REG_FIFO, dst, size); } void SX1278Lora::writeFifo(uint8_t addr, uint8_t *src, uint8_t size) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_FIFO_ADDR_PTR, addr); spi.writeRegisters(REG_FIFO, src, size); } @@ -393,20 +393,20 @@ SX1278::DioMask SX1278Lora::getDioMaskFromIrqFlags(IrqFlags flags, Mode _mode, ISX1278::IrqFlags SX1278Lora::getIrqFlags() { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); return spi.readRegister(REG_IRQ_FLAGS); } void SX1278Lora::resetIrqFlags(IrqFlags flags) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); // Register is write clear spi.writeRegister(REG_IRQ_FLAGS, flags); } void SX1278Lora::setMode(ISX1278::Mode mode) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister( REG_OP_MODE, @@ -415,7 +415,7 @@ void SX1278Lora::setMode(ISX1278::Mode mode) void SX1278Lora::setMapping(SX1278::DioMapping mapping) { - SPITransaction spi(slave, SPITransaction::WriteBit::INVERTED); + SPITransaction spi(slave); spi.writeRegister(REG_DIO_MAPPING_1, mapping.raw >> 8); spi.writeRegister(REG_DIO_MAPPING_2, mapping.raw); } diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp index 2ae8e6208..5ef25822f 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp @@ -127,7 +127,9 @@ int main() SPIBusConfig spi_config = {}; spi_config.clockDivider = SPI::ClockDivider::DIV_64; spi_config.mode = SPI::Mode::MODE_0; - spi_config.bitOrder = SPI::BitOrder::MSB_FIRST; + spi_config.bitOrder = SPI::Order::MSB_FIRST; + spi_config.byteOrder = SPI::Order::MSB_FIRST; + spi_config.writeBit = SPI::WriteBit::INVERTED; sx1278 = new SX1278Fsk(SPISlave(bus, cs, spi_config)); diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp index 3156a377a..f56c8200b 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp @@ -119,7 +119,9 @@ int main() SPIBusConfig spi_config = {}; spi_config.clockDivider = SPI::ClockDivider::DIV_64; spi_config.mode = SPI::Mode::MODE_0; - spi_config.bitOrder = SPI::BitOrder::MSB_FIRST; + spi_config.bitOrder = SPI::Order::MSB_FIRST; + spi_config.byteOrder = SPI::Order::MSB_FIRST; + spi_config.writeBit = SPI::WriteBit::INVERTED; sx1278 = new SX1278Fsk(SPISlave(bus, cs, spi_config)); diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp index 828b9733e..cb6180630 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp @@ -144,7 +144,9 @@ int main() SPIBusConfig spi_config = {}; spi_config.clockDivider = SPI::ClockDivider::DIV_64; spi_config.mode = SPI::Mode::MODE_0; - spi_config.bitOrder = SPI::BitOrder::MSB_FIRST; + spi_config.bitOrder = SPI::Order::MSB_FIRST; + spi_config.byteOrder = SPI::Order::MSB_FIRST; + spi_config.writeBit = SPI::WriteBit::INVERTED; sx1278 = new EbyteFsk(SPISlave(bus, cs, spi_config), txen::getPin(), rxen::getPin()); diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp index fba3c8bd5..6fb0a6173 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp @@ -164,7 +164,9 @@ int main() SPIBusConfig spi_config; spi_config.clockDivider = SPI::ClockDivider::DIV_64; spi_config.mode = SPI::Mode::MODE_0; - spi_config.bitOrder = SPI::BitOrder::MSB_FIRST; + spi_config.bitOrder = SPI::Order::MSB_FIRST; + spi_config.byteOrder = SPI::Order::MSB_FIRST; + spi_config.writeBit = SPI::WriteBit::INVERTED; sx1278 = new SX1278Fsk(SPISlave(bus, cs, spi_config)); diff --git a/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp b/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp index 08b0c7e71..b2d66e80b 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp @@ -188,7 +188,9 @@ int main() SPIBusConfig spi_config = {}; spi_config.clockDivider = SPI::ClockDivider::DIV_64; spi_config.mode = SPI::Mode::MODE_0; - spi_config.bitOrder = SPI::BitOrder::MSB_FIRST; + spi_config.bitOrder = SPI::Order::MSB_FIRST; + spi_config.byteOrder = SPI::Order::MSB_FIRST; + spi_config.writeBit = SPI::WriteBit::INVERTED; #ifdef IS_EBYTE sx1278 = new EbyteLora(SPISlave(bus, cs, spi_config), txen::getPin(), diff --git a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp index 88422766f..65d312671 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp @@ -198,7 +198,9 @@ int main() SPIBusConfig spi_config = {}; spi_config.clockDivider = SPI::ClockDivider::DIV_64; spi_config.mode = SPI::Mode::MODE_0; - spi_config.bitOrder = SPI::BitOrder::MSB_FIRST; + spi_config.bitOrder = SPI::Order::MSB_FIRST; + spi_config.byteOrder = SPI::Order::MSB_FIRST; + spi_config.writeBit = SPI::WriteBit::INVERTED; #ifdef IS_EBYTE sx1278 = new EbyteLora(SPISlave(bus, cs, spi_config), txen::getPin(), diff --git a/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp b/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp index 4653b87f0..694c68daa 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp @@ -118,7 +118,9 @@ int main() SPIBusConfig spi_config = {}; spi_config.clockDivider = SPI::ClockDivider::DIV_64; spi_config.mode = SPI::Mode::MODE_0; - spi_config.bitOrder = SPI::BitOrder::MSB_FIRST; + spi_config.bitOrder = SPI::Order::MSB_FIRST; + spi_config.byteOrder = SPI::Order::MSB_FIRST; + spi_config.writeBit = SPI::WriteBit::INVERTED; #ifdef IS_EBYTE sx1278 = new EbyteLora(SPISlave(bus, cs, spi_config), txen::getPin(), -- GitLab