diff --git a/.vscode/settings.json b/.vscode/settings.json index 66dd1b5820d9d5c4a599602b87f23eac419e33df..fa393981b857a5dbcae6300ee78bf8cd29a623cb 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -154,6 +154,7 @@ "cyaw", "DATABUS", "datasheet", + "Davide", "deleteme", "DMEIE", "Doxyfile", @@ -274,6 +275,7 @@ "Riccardo", "RQCP", "RXCRCR", + "Rssi", "RXIRQ", "RXNE", "RXNEIE", diff --git a/src/shared/radio/SX1278/Ebyte.h b/src/shared/radio/SX1278/Ebyte.h index c7e22a5d7330a6545c8ca8992b5d3cb8b3163b02..1ffc1df29f4e475e158aff24ea3b8e66504123f5 100644 --- a/src/shared/radio/SX1278/Ebyte.h +++ b/src/shared/radio/SX1278/Ebyte.h @@ -36,9 +36,10 @@ namespace Boardcore class EbyteFsk : public SX1278Fsk { public: - EbyteFsk(SPISlave slave, miosix::GpioPin tx_enable, - miosix::GpioPin rx_enable) - : SX1278Fsk(slave), tx_enable(tx_enable), rx_enable(rx_enable) + EbyteFsk(SPIBus &bus, miosix::GpioPin cs, SPI::ClockDivider clock_divider, + miosix::GpioPin tx_enable, miosix::GpioPin rx_enable) + : SX1278Fsk(bus, cs, clock_divider), tx_enable(tx_enable), + rx_enable(rx_enable) { // Make sure both the frontends are disabled! tx_enable.low(); @@ -63,9 +64,10 @@ private: class EbyteLora : public SX1278Lora { public: - EbyteLora(SPISlave slave, miosix::GpioPin tx_enable, - miosix::GpioPin rx_enable) - : SX1278Lora(slave), tx_enable(tx_enable), rx_enable(rx_enable) + EbyteLora(SPIBus &bus, miosix::GpioPin cs, SPI::ClockDivider clock_divider, + miosix::GpioPin tx_enable, miosix::GpioPin rx_enable) + : SX1278Lora(bus, cs, clock_divider), tx_enable(tx_enable), + rx_enable(rx_enable) { // Make sure both the frontends are disabled! tx_enable.low(); diff --git a/src/shared/radio/SX1278/SX1278Common.h b/src/shared/radio/SX1278/SX1278Common.h index 0fee45b8cec93663327b98368a6d2a4581a9485c..885702227c9eab93e2dfd14c1898267fb7baadc3 100644 --- a/src/shared/radio/SX1278/SX1278Common.h +++ b/src/shared/radio/SX1278/SX1278Common.h @@ -111,7 +111,11 @@ public: void handleDioIRQ(Dio dio); protected: - explicit SX1278Common(SPISlave slave) : slave(slave) {} + explicit SX1278Common(SPIBus &bus, miosix::GpioPin cs, + SPI::ClockDivider clock_divider) + : slave(SPISlave(bus, cs, getSpiBusConfig(clock_divider))) + { + } /** * @brief RAII scoped bus lock guard. diff --git a/src/shared/radio/SX1278/SX1278Defs.h b/src/shared/radio/SX1278/SX1278Defs.h index e524279a806bd3685b2825f2393401a1ab2f4681..12701d83d5526db55cec4de0ca15551cb0bbd3b4 100644 --- a/src/shared/radio/SX1278/SX1278Defs.h +++ b/src/shared/radio/SX1278/SX1278Defs.h @@ -22,6 +22,7 @@ #pragma once +#include <drivers/spi/SPIBusInterface.h> #include <cstdint> namespace Boardcore @@ -40,6 +41,18 @@ constexpr int FXOSC = 32000000; */ constexpr float FSTEP = 61.03515625; +inline SPIBusConfig getSpiBusConfig(SPI::ClockDivider clock_divider) +{ + SPIBusConfig bus_config = {}; + bus_config.clockDivider = clock_divider; + bus_config.mode = SPI::Mode::MODE_0; + bus_config.bitOrder = SPI::Order::MSB_FIRST; + bus_config.byteOrder = SPI::Order::MSB_FIRST; + bus_config.writeBit = SPI::WriteBit::INVERTED; + + return bus_config; +} + /** * @brief Represents a DIO.. */ @@ -301,12 +314,12 @@ namespace RegImageCal { constexpr uint8_t AUTO_IMAGE_CAL_ON = 0x80; -enum TempTreshold +enum TempThreshold { - TEMP_TRESHOLD_5DEG = 0x00, - TEMP_TRESHOLD_10DEG = 0x02, - TEMP_TRESHOLD_15DEG = 0x04, - TEMP_TRESHOLD_20DEG = 0x06, + TEMP_THRESHOLD_5DEG = 0x00, + TEMP_THRESHOLD_10DEG = 0x02, + TEMP_THRESHOLD_15DEG = 0x04, + TEMP_THRESHOLD_20DEG = 0x06, }; constexpr uint8_t TEMP_MONITOR_OFF = 0x01; @@ -420,7 +433,7 @@ static constexpr int DIO_MAPPINGS[6][8][4] = [RegOpMode::MODE_STDBY] = {0, 0, 0, RegIrqFlags::LOW_BAT}, [RegOpMode::MODE_FSTX] = {0, 0, 0, RegIrqFlags::LOW_BAT}, [RegOpMode::MODE_TX] = {RegIrqFlags::PACKET_SENT, 0, 0, - RegIrqFlags::LOW_BAT}, + RegIrqFlags::LOW_BAT}, [RegOpMode::MODE_FSRX] = {0, 0, 0, RegIrqFlags::LOW_BAT}, [RegOpMode::MODE_RX] = {RegIrqFlags::PAYLOAD_READY, RegIrqFlags::CRC_OK, 0, @@ -518,11 +531,11 @@ static constexpr int DIO_MAPPINGS[6][8][4] = [RegOpMode::MODE_SLEEP] = {0, 0, 0, 0}, [RegOpMode::MODE_STDBY] = {RegIrqFlags::LOW_BAT, 0, 0, 0}, [RegOpMode::MODE_FSTX] = {RegIrqFlags::LOW_BAT, - RegIrqFlags::PILL_LOCK, 0, 0}, + RegIrqFlags::PILL_LOCK, 0, 0}, [RegOpMode::MODE_TX] = {RegIrqFlags::LOW_BAT, - RegIrqFlags::PILL_LOCK, 0, 0}, + RegIrqFlags::PILL_LOCK, 0, 0}, [RegOpMode::MODE_FSRX] = {RegIrqFlags::LOW_BAT, - RegIrqFlags::PILL_LOCK, 0, 0}, + RegIrqFlags::PILL_LOCK, 0, 0}, [RegOpMode::MODE_RX] = {RegIrqFlags::LOW_BAT, RegIrqFlags::PILL_LOCK, RegIrqFlags::TIMEOUT, @@ -532,14 +545,14 @@ static constexpr int DIO_MAPPINGS[6][8][4] = [RegOpMode::MODE_SLEEP] = {0, 0, 0, 0}, [RegOpMode::MODE_STDBY] = {0, 0, 0, RegIrqFlags::MODE_READY}, [RegOpMode::MODE_FSTX] = {0, RegIrqFlags::PILL_LOCK, 0, - RegIrqFlags::MODE_READY}, + RegIrqFlags::MODE_READY}, [RegOpMode::MODE_TX] = {0, RegIrqFlags::PILL_LOCK, 0, - RegIrqFlags::MODE_READY}, + RegIrqFlags::MODE_READY}, [RegOpMode::MODE_FSRX] = {0, RegIrqFlags::PILL_LOCK, 0, RegIrqFlags::MODE_READY}, [RegOpMode::MODE_RX] = {0, RegIrqFlags::PILL_LOCK, 0, - RegIrqFlags::MODE_READY}, + RegIrqFlags::MODE_READY}, }}; } // namespace Fsk diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp index dcf556af72627a216de1873475a10872f3db0e65..b43ac5acbceda513fa765123ab0e804bd066fcf9 100644 --- a/src/shared/radio/SX1278/SX1278Fsk.cpp +++ b/src/shared/radio/SX1278/SX1278Fsk.cpp @@ -44,7 +44,7 @@ constexpr uint8_t REG_SYNC_CONFIG_DEFAULT = RegSyncConfig::AUTO_RESTART_RX_MODE_OFF | RegSyncConfig::PREAMBLE_POLARITY_55 | RegSyncConfig::SYNC_ON; -constexpr uint8_t REG_IMAGE_CAL_DEFAULT = RegImageCal::TEMP_TRESHOLD_10DEG; +constexpr uint8_t REG_IMAGE_CAL_DEFAULT = RegImageCal::TEMP_THRESHOLD_10DEG; // Enable: // - PayloadReady, PacketSent on DIO0 (mode 00) @@ -263,11 +263,7 @@ DioMask SX1278Fsk::getDioMaskFromIrqFlags(IrqFlags flags, Mode mode, ISX1278::IrqFlags SX1278Fsk::getIrqFlags() { SPITransaction spi(slave); - - uint8_t flags_msb = spi.readRegister(REG_IRQ_FLAGS_1); - uint8_t flags_lsb = spi.readRegister(REG_IRQ_FLAGS_2); - - return (flags_msb << 8 | flags_lsb); + return spi.readRegister16(REG_IRQ_FLAGS_1); } void SX1278Fsk::resetIrqFlags(IrqFlags flags) @@ -280,8 +276,7 @@ void SX1278Fsk::resetIrqFlags(IrqFlags flags) if (flags != 0) { SPITransaction spi(slave); - spi.writeRegister(REG_IRQ_FLAGS_1, flags >> 8); - spi.writeRegister(REG_IRQ_FLAGS_2, flags); + spi.writeRegister16(REG_IRQ_FLAGS_1, flags); } } @@ -289,21 +284,18 @@ float SX1278Fsk::getRssi() { SPITransaction spi(slave); - return static_cast<float>(spi.readRegister(REG_RSSI_VALUE)) * -0.5f; + uint8_t rssi_raw = spi.readRegister(REG_RSSI_VALUE); + + return static_cast<float>(rssi_raw) * -0.5f; } float SX1278Fsk::getFei() { SPITransaction spi(slave); - // Order of read is important!! - uint8_t fei_msb = spi.readRegister(REG_FEI_MSB); - uint8_t fei_lsb = spi.readRegister(REG_FEI_LSB); - - uint16_t fei = (static_cast<uint16_t>(fei_msb) << 8) | - (static_cast<uint16_t>(fei_lsb)); + uint16_t fei_raw = spi.readRegister16(REG_FEI_MSB); - return static_cast<float>(fei) * FSTEP; + return static_cast<float>(fei_raw) * FSTEP; } void SX1278Fsk::setMode(Mode mode) @@ -315,8 +307,7 @@ void SX1278Fsk::setMode(Mode mode) void SX1278Fsk::setMapping(SX1278::DioMapping mapping) { SPITransaction spi(slave); - spi.writeRegister(REG_DIO_MAPPING_1, mapping.raw >> 8); - spi.writeRegister(REG_DIO_MAPPING_2, mapping.raw); + spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw); } void SX1278Fsk::setBitrate(int bitrate) @@ -325,16 +316,14 @@ void SX1278Fsk::setBitrate(int bitrate) // Update values SPITransaction spi(slave); - spi.writeRegister(REG_BITRATE_MSB, val >> 8); - spi.writeRegister(REG_BITRATE_LSB, val); + spi.writeRegister16(REG_BITRATE_MSB, val); } void SX1278Fsk::setFreqDev(int freq_dev) { uint16_t val = freq_dev / FSTEP; SPITransaction spi(slave); - spi.writeRegister(REG_FDEV_MSB, (val >> 8) & 0x3f); - spi.writeRegister(REG_FDEV_LSB, val); + spi.writeRegister16(REG_FDEV_MSB, val & 0x3fff); } void SX1278Fsk::setFreqRF(int freq_rf) @@ -343,9 +332,7 @@ void SX1278Fsk::setFreqRF(int freq_rf) // Update values SPITransaction spi(slave); - spi.writeRegister(REG_FRF_MSB, val >> 16); - spi.writeRegister(REG_FRF_MID, val >> 8); - spi.writeRegister(REG_FRF_LSB, val); + spi.writeRegister24(REG_FRF_MSB, val); } void SX1278Fsk::setOcp(int ocp) @@ -393,8 +380,7 @@ void SX1278Fsk::setAfcBw(RxBw afc_bw) void SX1278Fsk::setPreambleLen(int len) { SPITransaction spi(slave); - spi.writeRegister(REG_PREAMBLE_MSB, len >> 8); - spi.writeRegister(REG_PREAMBLE_LSB, len); + spi.writeRegister16(REG_PREAMBLE_MSB, len); } void SX1278Fsk::setPa(int power, bool pa_boost) @@ -439,84 +425,4 @@ void SX1278Fsk::setShaping(Shaping shaping) spi.writeRegister(REG_PA_RAMP, static_cast<uint8_t>(shaping) | 0x09); } -void SX1278Fsk::debugDumpRegisters() -{ - Lock guard(*this); - struct RegDef - { - const char *name; - int addr; - }; - - const RegDef defs[] = { - RegDef{"REG_OP_MODE", REG_OP_MODE}, - RegDef{"REG_BITRATE_MSB", REG_BITRATE_MSB}, - RegDef{"REG_BITRATE_LSB", REG_BITRATE_LSB}, - RegDef{"REG_FDEV_MSB", REG_FDEV_MSB}, - RegDef{"REG_FDEV_LSB", REG_FDEV_LSB}, - RegDef{"REG_FRF_MSB", REG_FRF_MSB}, RegDef{"REG_FRF_MID", REG_FRF_MID}, - RegDef{"REG_FRF_LSB", REG_FRF_LSB}, - RegDef{"REG_PA_CONFIG", REG_PA_CONFIG}, - RegDef{"REG_PA_RAMP", REG_PA_RAMP}, RegDef{"REG_OCP", REG_OCP}, - RegDef{"REG_LNA", REG_LNA}, RegDef{"REG_RX_CONFIG", REG_RX_CONFIG}, - RegDef{"REG_RSSI_CONFIG", REG_RSSI_CONFIG}, - RegDef{"REG_RSSI_COLLISION", REG_RSSI_COLLISION}, - RegDef{"REG_RSSI_THRESH", REG_RSSI_THRESH}, - // RegDef { "REG_RSSI_VALUE", REG_RSSI_VALUE }, - RegDef{"REG_RX_BW", REG_RX_BW}, RegDef{"REG_AFC_BW", REG_AFC_BW}, - RegDef{"REG_OOK_PEAK", REG_OOK_PEAK}, - RegDef{"REG_OOK_FIX", REG_OOK_FIX}, RegDef{"REG_OOK_AVG", REG_OOK_AVG}, - RegDef{"REG_AFC_FEI", REG_AFC_FEI}, RegDef{"REG_AFC_MSB", REG_AFC_MSB}, - RegDef{"REG_AFC_LSB", REG_AFC_LSB}, RegDef{"REG_FEI_MSB", REG_FEI_MSB}, - RegDef{"REG_FEI_LSB", REG_FEI_LSB}, - RegDef{"REG_PREAMBLE_DETECT", REG_PREAMBLE_DETECT}, - RegDef{"REG_RX_TIMEOUT_1", REG_RX_TIMEOUT_1}, - RegDef{"REG_RX_TIMEOUT_2", REG_RX_TIMEOUT_2}, - RegDef{"REG_RX_TIMEOUT_3", REG_RX_TIMEOUT_3}, - RegDef{"REG_RX_DELAY", REG_RX_DELAY}, RegDef{"REG_OSC", REG_OSC}, - RegDef{"REG_PREAMBLE_MSB", REG_PREAMBLE_MSB}, - RegDef{"REG_PREAMBLE_LSB", REG_PREAMBLE_LSB}, - RegDef{"REG_SYNC_CONFIG", REG_SYNC_CONFIG}, - RegDef{"REG_SYNC_VALUE_1", REG_SYNC_VALUE_1}, - RegDef{"REG_SYNC_VALUE_2", REG_SYNC_VALUE_2}, - RegDef{"REG_SYNC_VALUE_3", REG_SYNC_VALUE_3}, - RegDef{"REG_SYNC_VALUE_4", REG_SYNC_VALUE_4}, - RegDef{"REG_SYNC_VALUE_5", REG_SYNC_VALUE_5}, - RegDef{"REG_SYNC_VALUE_6", REG_SYNC_VALUE_6}, - RegDef{"REG_SYNC_VALUE_7", REG_SYNC_VALUE_7}, - RegDef{"REG_SYNC_VALUE_8", REG_SYNC_VALUE_8}, - RegDef{"REG_PACKET_CONFIG_1", REG_PACKET_CONFIG_1}, - RegDef{"REG_PACKET_CONFIG_2", REG_PACKET_CONFIG_2}, - RegDef{"REG_PACKET_PAYLOAD_LENGTH", REG_PACKET_PAYLOAD_LENGTH}, - RegDef{"REG_NODE_ADRS", REG_NODE_ADRS}, - RegDef{"REG_BROADCAST_ADRS", REG_BROADCAST_ADRS}, - RegDef{"REG_FIFO_THRESH", REG_FIFO_THRESH}, - RegDef{"REG_SEQ_CONFIG_1", REG_SEQ_CONFIG_1}, - RegDef{"REG_SEQ_CONFIG_2", REG_SEQ_CONFIG_2}, - RegDef{"REG_TIMER_RESOL", REG_TIMER_RESOL}, - RegDef{"REG_TIMER_1_COEF", REG_TIMER_1_COEF}, - RegDef{"REG_TIMER_2_COEF", REG_TIMER_2_COEF}, - RegDef{"REG_IMAGE_CAL", REG_IMAGE_CAL}, - // RegDef { "REG_TEMP", REG_TEMP }, - RegDef{"REG_LOW_BAT", REG_LOW_BAT}, - // RegDef { "REG_IRQ_FLAGS_1", REG_IRQ_FLAGS_1 }, - // RegDef { "REG_IRQ_FLAGS_2", REG_IRQ_FLAGS_2 }, - RegDef{"REG_DIO_MAPPING_1", REG_DIO_MAPPING_1}, - RegDef{"REG_DIO_MAPPING_2", REG_DIO_MAPPING_2}, - RegDef{"REG_VERSION", REG_VERSION}, RegDef{NULL, 0}}; - - SPITransaction spi(slave); - - int i = 0; - while (defs[i].name) - { - auto name = defs[i].name; - auto addr = defs[i].addr; - - LOG_DEBUG(logger, "%s: 0x%x\n", name, spi.readRegister(addr)); - - i++; - } -} - } // namespace Boardcore diff --git a/src/shared/radio/SX1278/SX1278Fsk.h b/src/shared/radio/SX1278/SX1278Fsk.h index 300780978ceec32e8b776012ffdaaf798d63b613..3b054fa95e3c6ea7dc2010031ce0a0ed3e405373 100644 --- a/src/shared/radio/SX1278/SX1278Fsk.h +++ b/src/shared/radio/SX1278/SX1278Fsk.h @@ -122,11 +122,12 @@ public: /** * @brief Construct a new SX1278 - * - * @param bus SPI bus used. - * @param cs Chip select pin. */ - explicit SX1278Fsk(SPISlave slave) : SX1278Common(slave) {} + explicit SX1278Fsk(SPIBus &bus, miosix::GpioPin cs, + SPI::ClockDivider clock_divider) + : SX1278Common(bus, cs, clock_divider) + { + } /** * @brief Setup the device. @@ -178,11 +179,6 @@ public: */ float getLastRxFei(); - /** - * @brief Dump all registers via TRACE. - */ - void debugDumpRegisters(); - protected: // Stuff to work with various front-ends virtual void enableRxFrontend() override {} diff --git a/src/shared/radio/SX1278/SX1278Lora.cpp b/src/shared/radio/SX1278/SX1278Lora.cpp index 08162a5ac1e9b13dd5ba4638628197e86b4280bd..60958050f28441249886a2774802be514bc33e92 100644 --- a/src/shared/radio/SX1278/SX1278Lora.cpp +++ b/src/shared/radio/SX1278/SX1278Lora.cpp @@ -198,9 +198,7 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config) // Setup frequency uint32_t freq_rf_raw = errata_values.freq_rf / FSTEP; - spi.writeRegister(REG_FRF_MSB, freq_rf_raw >> 16); - spi.writeRegister(REG_FRF_MID, freq_rf_raw >> 8); - spi.writeRegister(REG_FRF_LSB, freq_rf_raw); + spi.writeRegister24(REG_FRF_MSB, freq_rf_raw); // Setup reg power amplifier const int MAX_POWER = 0b111; @@ -416,8 +414,7 @@ void SX1278Lora::setMode(ISX1278::Mode mode) void SX1278Lora::setMapping(SX1278::DioMapping mapping) { SPITransaction spi(slave); - spi.writeRegister(REG_DIO_MAPPING_1, mapping.raw >> 8); - spi.writeRegister(REG_DIO_MAPPING_2, mapping.raw); + spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw); } } // namespace Boardcore diff --git a/src/shared/radio/SX1278/SX1278Lora.h b/src/shared/radio/SX1278/SX1278Lora.h index 3d129fac0406f4ec2218ab1006140e5e4171a2ee..f7d562bbcc5ed0a0b80b98edd38ef04651b6e652 100644 --- a/src/shared/radio/SX1278/SX1278Lora.h +++ b/src/shared/radio/SX1278/SX1278Lora.h @@ -133,7 +133,14 @@ public: IRQ_TIMEOUT, //< Timeout on IRQ register. }; - explicit SX1278Lora(SPISlave slave) : SX1278Common(slave) {} + /** + * @brief Construct a new SX1278 + */ + explicit SX1278Lora(SPIBus &bus, miosix::GpioPin cs, + SPI::ClockDivider clock_divider) + : SX1278Common(bus, cs, clock_divider) + { + } /** * @brief Setup the device. 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 5ef25822fa303630a8d1de04d746440bd2808e49..5facf054cee370b5a43d7b2ab80717cb5e3eed80 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp @@ -124,14 +124,7 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - SPIBusConfig spi_config = {}; - spi_config.clockDivider = SPI::ClockDivider::DIV_64; - spi_config.mode = SPI::Mode::MODE_0; - 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)); + sx1278 = new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64); printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE) 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 f56c8200bb5e93d799999b1c23a5af8b98a79b14..9a1ad3f8ad7830e6ab2266fdcf6822d4fcb46b9a 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp @@ -116,14 +116,7 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - SPIBusConfig spi_config = {}; - spi_config.clockDivider = SPI::ClockDivider::DIV_64; - spi_config.mode = SPI::Mode::MODE_0; - 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)); + sx1278 = new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64); printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE) diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp index cb6180630a07edea2d0c5b08fa1da079abbde1b8..6c9c47e915029e17f4bf46d1fbfdc25065a19146 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp @@ -141,15 +141,7 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - SPIBusConfig spi_config = {}; - spi_config.clockDivider = SPI::ClockDivider::DIV_64; - spi_config.mode = SPI::Mode::MODE_0; - 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()); + sx1278 = new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64); printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE) diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp index 6fb0a6173e02555ede22cf430c518f6620843611..01ba90c63de9aa33c815c1bd29fd999deab6a0ff 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp @@ -161,14 +161,7 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - SPIBusConfig spi_config; - spi_config.clockDivider = SPI::ClockDivider::DIV_64; - spi_config.mode = SPI::Mode::MODE_0; - 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)); + sx1278 = new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64); printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE) diff --git a/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp b/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp index b2d66e80b9b621fed25d7bd56e9a6904731b75ae..3a96bc45740fb3b3497eb37ced0aa4039131a0dd 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp @@ -185,18 +185,11 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - SPIBusConfig spi_config = {}; - spi_config.clockDivider = SPI::ClockDivider::DIV_64; - spi_config.mode = SPI::Mode::MODE_0; - 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(), + sx1278 = new EbyteLora(bus, cs, SPI::ClockDivider::DIV_64, txen::getPin(), rxen::getPin()); #else - sx1278 = new SX1278Lora(SPISlave(bus, cs, spi_config)); + sx1278 = new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64); #endif printf("\n[sx1278] Configuring sx1278...\n"); diff --git a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp index 65d31267144a7ba27052abb6321c4d55b14b7e49..8d30102caec14b0fe066ba9af9a6898076c0f78c 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp @@ -195,18 +195,11 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - SPIBusConfig spi_config = {}; - spi_config.clockDivider = SPI::ClockDivider::DIV_64; - spi_config.mode = SPI::Mode::MODE_0; - 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(), + sx1278 = new EbyteLora(bus, cs, SPI::ClockDivider::DIV_64, txen::getPin(), rxen::getPin()); #else - sx1278 = new SX1278Lora(SPISlave(bus, cs, spi_config)); + sx1278 = new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64); #endif printf("\n[sx1278] Configuring sx1278...\n"); diff --git a/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp b/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp index 694c68daac00f13243d29d7f8b07c8d7c09e7278..9d19c6cecffeb38a663bc5646dac4911c4bb4e13 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp @@ -115,18 +115,14 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - SPIBusConfig spi_config = {}; - spi_config.clockDivider = SPI::ClockDivider::DIV_64; - spi_config.mode = SPI::Mode::MODE_0; - 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(); #ifdef IS_EBYTE - sx1278 = new EbyteLora(SPISlave(bus, cs, spi_config), txen::getPin(), + sx1278 = new EbyteLora(bus, cs, SPI::ClockDivider::DIV_64, txen::getPin(), rxen::getPin()); #else - sx1278 = new SX1278Lora(SPISlave(bus, cs, spi_config)); + sx1278 = new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64); #endif printf("\n[sx1278] Configuring sx1278...\n");