diff --git a/cmake/boardcore.cmake b/cmake/boardcore.cmake index 435e99a41e20199bf39d6353ba9e1dfc8fe970a2..2b621f0ac78ea8c67b4056aaf1b1a20575d8efcd 100644 --- a/cmake/boardcore.cmake +++ b/cmake/boardcore.cmake @@ -76,7 +76,6 @@ foreach(OPT_BOARD ${BOARDS}) ${SBS_BASE}/src/shared/radio/SX1278/SX1278Fsk.cpp ${SBS_BASE}/src/shared/radio/SX1278/SX1278Lora.cpp ${SBS_BASE}/src/shared/radio/SX1278/SX1278Common.cpp - ${SBS_BASE}/src/shared/radio/SX1278/Ebyte.cpp # Scheduler ${SBS_BASE}/src/shared/scheduler/TaskScheduler.cpp diff --git a/src/entrypoints/sx1278-serial.cpp b/src/entrypoints/sx1278-serial.cpp index 72fdc096eb46ba30099744d763b85097c24a50a7..f3f567beaac1b686de681d0dbe86bf9cb3612bb4 100644 --- a/src/entrypoints/sx1278-serial.cpp +++ b/src/entrypoints/sx1278-serial.cpp @@ -24,7 +24,7 @@ #include <filesystem/console/console_device.h> // SX1278 includes -#include <radio/SX1278/Ebyte.h> +#include <radio/SX1278/SX1278Frontends.h> #include <radio/SX1278/SX1278Fsk.h> #include <radio/SX1278/SX1278Lora.h> @@ -170,20 +170,22 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - SPISlave spi(bus, cs, spi_config); +#ifdef IS_EBYTE + std::unique_ptr<SX1278::ISX1278Frontend> frontend( + new EbyteFrontend(txen::getPin(), rxen::getPin())); +#else + std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); +#endif #ifdef SX1278_IS_LORA // Run default configuration SX1278Lora::Config config; SX1278Lora::Error err; -#ifdef SX1278_IS_EBYTE - sx1278 = new EbyteLora(spi, txen::getPin(), rxen::getPin()); -#else - sx1278 = new SX1278Lora(spi); -#endif + sx1278 = + new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); - printf("\n[sx1278] Configuring sx1278...\n"); + printf("\n[sx1278] Configuring sx1278 lora...\n"); if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE) { printf("[sx1278] sx1278->init error\n"); @@ -196,16 +198,13 @@ int main() SX1278Fsk::Config config; SX1278Fsk::Error err; -#ifdef SX1278_IS_EBYTE - sx1278 = new EbyteFsk(spi, txen::getPin(), rxen::getPin()); -#else - sx1278 = new SX1278Fsk(spi); -#endif + sx1278 = + new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); - printf("\n[sx1278] Configuring sx1278...\n"); + printf("\n[sx1278] Configuring sx1278 fsk...\n"); if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE) { - // FIXME: Why does clang-format put this line up here? + // FIXME: Why does clang-format put this line up here? printf("[sx1278] sx1278->init error\n"); return -1; } diff --git a/src/shared/radio/SX1278/Ebyte.cpp b/src/shared/radio/SX1278/Ebyte.cpp deleted file mode 100644 index 8ac662783c0eb1d26869326d19119b43cf81b819..0000000000000000000000000000000000000000 --- a/src/shared/radio/SX1278/Ebyte.cpp +++ /dev/null @@ -1,50 +0,0 @@ -/* Copyright (c) 2022 Skyward Experimental Rocketry - * Author: Davide Mor - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#include "Ebyte.h" - -namespace Boardcore -{ - -EbyteFsk::Error EbyteFsk::configure(const Config& config) -{ - // TODO(davide.mor): Validate input parameters - return SX1278Fsk::configure(config); -} - -void EbyteFsk::enableRxFrontend() { rx_enable.high(); } -void EbyteFsk::disableRxFrontend() { rx_enable.low(); } -void EbyteFsk::enableTxFrontend() { tx_enable.high(); } -void EbyteFsk::disableTxFrontend() { tx_enable.low(); } - -EbyteLora::Error EbyteLora::configure(const Config& config) -{ - // TODO(davide.mor): Validate input parameters - return SX1278Lora::configure(config); -} - -void EbyteLora::enableRxFrontend() { rx_enable.high(); } -void EbyteLora::disableRxFrontend() { rx_enable.low(); } -void EbyteLora::enableTxFrontend() { tx_enable.high(); } -void EbyteLora::disableTxFrontend() { tx_enable.low(); } - -} // namespace Boardcore diff --git a/src/shared/radio/SX1278/Ebyte.h b/src/shared/radio/SX1278/Ebyte.h deleted file mode 100644 index 1ffc1df29f4e475e158aff24ea3b8e66504123f5..0000000000000000000000000000000000000000 --- a/src/shared/radio/SX1278/Ebyte.h +++ /dev/null @@ -1,89 +0,0 @@ -/* Copyright (c) 2022 Skyward Experimental Rocketry - * Author: Davide Mor - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#pragma once - -#include <miosix.h> - -#include "SX1278Fsk.h" -#include "SX1278Lora.h" - -namespace Boardcore -{ - -/** - * @brief Specialized SX1278 driver for the E32 400M30S module - */ -class EbyteFsk : public SX1278Fsk -{ -public: - 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(); - rx_enable.low(); - } - - [[nodiscard]] Error configure(const Config &config) override; - -private: - void enableRxFrontend() override; - void disableRxFrontend() override; - void enableTxFrontend() override; - void disableTxFrontend() override; - - miosix::GpioPin tx_enable; - miosix::GpioPin rx_enable; -}; - -/** - * @brief Specialized SX1278 driver for the E32 400M30S module - */ -class EbyteLora : public SX1278Lora -{ -public: - 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(); - rx_enable.low(); - } - - [[nodiscard]] Error configure(const Config &config) override; - -private: - void enableRxFrontend() override; - void disableRxFrontend() override; - void enableTxFrontend() override; - void disableTxFrontend() override; - - miosix::GpioPin tx_enable; - miosix::GpioPin rx_enable; -}; - -} // namespace Boardcore diff --git a/src/shared/radio/SX1278/SX1278Common.cpp b/src/shared/radio/SX1278/SX1278Common.cpp index 08b03a30126972efbd0e50c0ec75541a6fe6500d..8f7a5f0dd97daac81d6857cd020a53d9e86ebfbb 100644 --- a/src/shared/radio/SX1278/SX1278Common.cpp +++ b/src/shared/radio/SX1278/SX1278Common.cpp @@ -149,6 +149,10 @@ bool SX1278Common::checkForIrqAndReset(IrqFlags irq) } } +ISX1278Frontend &SX1278Common::getFrontend() { return *frontend; } + +SPISlave &SX1278Common::getSpiSlave() { return slave; } + SX1278Common::DeviceState SX1278Common::lockMode(Mode mode, DioMapping mapping, bool tx_frontend, bool rx_frontend) @@ -185,23 +189,23 @@ void SX1278Common::enterMode(Mode mode, DioMapping mapping, // First disable all of the frontend if necessary if (set_tx_frontend_on != state.is_tx_frontend_on && !set_tx_frontend_on) { - disableTxFrontend(); + getFrontend().disableTx(); } if (set_rx_frontend_on != state.is_rx_frontend_on && !set_rx_frontend_on) { - disableRxFrontend(); + getFrontend().disableRx(); } // Then enable the newly requested ones if (set_tx_frontend_on != state.is_tx_frontend_on && set_tx_frontend_on) { - enableTxFrontend(); + getFrontend().enableTx(); } if (set_rx_frontend_on != state.is_rx_frontend_on && set_rx_frontend_on) { - enableRxFrontend(); + getFrontend().enableRx(); } state.is_tx_frontend_on = set_tx_frontend_on; diff --git a/src/shared/radio/SX1278/SX1278Common.h b/src/shared/radio/SX1278/SX1278Common.h index 885702227c9eab93e2dfd14c1898267fb7baadc3..7471e0bc2c630deb93087cf461e54d71223c9396 100644 --- a/src/shared/radio/SX1278/SX1278Common.h +++ b/src/shared/radio/SX1278/SX1278Common.h @@ -26,6 +26,8 @@ #include <miosix.h> #include <radio/Transceiver.h> +#include <memory> + #include "SX1278Defs.h" namespace Boardcore @@ -76,11 +78,28 @@ protected: virtual DioMask getDioMaskFromIrqFlags(IrqFlags flags, Mode mode, DioMapping mapping) = 0; +}; + +/** + * @brief Shared interface between all SX1278 frontends + */ +class ISX1278Frontend +{ +public: + /** + * @brief Is this frontend connected to PA_BOOST or RFO_LF/_HF? + */ + virtual bool isOnPaBoost() = 0; - virtual void enableRxFrontend() = 0; - virtual void disableRxFrontend() = 0; - virtual void enableTxFrontend() = 0; - virtual void disableTxFrontend() = 0; + /** + * @brief What is the maximum power supported by this frontend? + */ + virtual int maxInPower() = 0; + + virtual void enableRx() = 0; + virtual void disableRx() = 0; + virtual void enableTx() = 0; + virtual void disableTx() = 0; }; class SX1278Common : public ISX1278 @@ -112,7 +131,8 @@ public: protected: explicit SX1278Common(SPIBus &bus, miosix::GpioPin cs, - SPI::ClockDivider clock_divider) + SPI::ClockDivider clock_divider, + std::unique_ptr<ISX1278Frontend>) : slave(SPISlave(bus, cs, getSpiBusConfig(clock_divider))) { } @@ -180,10 +200,9 @@ protected: */ bool checkForIrqAndReset(IrqFlags irq); - /** - * @brief The actual SPISlave, used by child classes. - */ - SPISlave slave; + ISX1278Frontend &getFrontend(); + + SPISlave &getSpiSlave(); private: DeviceState lockMode(Mode mode, DioMapping mapping, bool set_tx_frontend_on, @@ -198,6 +217,8 @@ private: miosix::FastMutex mutex; DeviceState state; + std::unique_ptr<ISX1278Frontend> frontend; + SPISlave slave; }; } // namespace SX1278 diff --git a/src/shared/radio/SX1278/SX1278Frontends.h b/src/shared/radio/SX1278/SX1278Frontends.h new file mode 100644 index 0000000000000000000000000000000000000000..ea87ed44cad3c9008e27c2b7dd7cc5ec841638e0 --- /dev/null +++ b/src/shared/radio/SX1278/SX1278Frontends.h @@ -0,0 +1,70 @@ +/* Copyright (c) 2023 Skyward Experimental Rocketry + * Author: Davide Mor + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#pragma once + +#include <miosix.h> + +#include "SX1278Common.h" + +namespace Boardcore +{ + +class EbyteFrontend : public SX1278::ISX1278Frontend +{ +public: + EbyteFrontend(miosix::GpioPin tx_enable, miosix::GpioPin rx_enable) + : tx_enable(tx_enable), rx_enable(rx_enable) + { + } + + bool isOnPaBoost() override { return true; } + int maxInPower() override + { + // TODO: Set this to a proper value, right now it's just guessed, the + // datasheet is just too cryptic, fucking chinese datasheet + return 15; + } + + void enableRx() override { rx_enable.high(); } + void disableRx() override { rx_enable.low(); } + void enableTx() override { tx_enable.high(); } + void disableTx() override { tx_enable.low(); } + +private: + miosix::GpioPin tx_enable; + miosix::GpioPin rx_enable; +}; + +class RA01Frontend : public SX1278::ISX1278Frontend +{ +public: + bool isOnPaBoost() override { return true; } + int maxInPower() override { return 17; } + + void enableRx() override {} + void disableRx() override {} + void enableTx() override {} + void disableTx() override {} +}; + +} // namespace Boardcore \ No newline at end of file diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp index b43ac5acbceda513fa765123ab0e804bd066fcf9..f074edeb530f73d1b17c786ea121b160d4ebb1c4 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 spi(getSpiSlave()); return spi.readRegister(REG_VERSION) == 0x12; } @@ -103,12 +103,16 @@ SX1278Fsk::Error SX1278Fsk::configure(const Config &config) uint8_t sync_word[2] = {0x12, 0xad}; setSyncWord(sync_word, 2); setPreambleLen(2); - setPa(config.power, config.pa_boost); setShaping(config.shaping); + // Make sure the PA matches settings with the frontend + int power = std::min(config.power, getFrontend().maxInPower()); + bool pa_boost = getFrontend().isOnPaBoost(); + setPa(power, pa_boost); + // Setup generic parameters { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister(REG_RX_CONFIG, RegRxConfig::AFC_AUTO_ON | RegRxConfig::AGC_AUTO_ON | @@ -155,7 +159,7 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len) last_rx_rssi = getRssi(); { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); len = spi.readRegister(REG_FIFO); if (len > max_len) return -1; @@ -186,7 +190,7 @@ bool SX1278Fsk::send(uint8_t *pkt, size_t len) waitForIrq(guard_mode, RegIrqFlags::TX_READY); { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister(REG_FIFO, static_cast<uint8_t>(len)); spi.writeRegisters(REG_FIFO, pkt, len); @@ -226,7 +230,7 @@ void SX1278Fsk::rateLimitTx() void SX1278Fsk::imageCalibrate() { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister(REG_IMAGE_CAL, REG_IMAGE_CAL_DEFAULT | (1 << 6)); // Wait for calibration complete by polling on running register @@ -262,7 +266,7 @@ DioMask SX1278Fsk::getDioMaskFromIrqFlags(IrqFlags flags, Mode mode, ISX1278::IrqFlags SX1278Fsk::getIrqFlags() { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); return spi.readRegister16(REG_IRQ_FLAGS_1); } @@ -275,14 +279,14 @@ void SX1278Fsk::resetIrqFlags(IrqFlags flags) if (flags != 0) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister16(REG_IRQ_FLAGS_1, flags); } } float SX1278Fsk::getRssi() { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); uint8_t rssi_raw = spi.readRegister(REG_RSSI_VALUE); @@ -291,7 +295,7 @@ float SX1278Fsk::getRssi() float SX1278Fsk::getFei() { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); uint16_t fei_raw = spi.readRegister16(REG_FEI_MSB); @@ -300,13 +304,13 @@ float SX1278Fsk::getFei() void SX1278Fsk::setMode(Mode mode) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister(REG_OP_MODE, REG_OP_MODE_DEFAULT | mode); } void SX1278Fsk::setMapping(SX1278::DioMapping mapping) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw); } @@ -315,14 +319,14 @@ void SX1278Fsk::setBitrate(int bitrate) uint16_t val = FXOSC / bitrate; // Update values - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister16(REG_BITRATE_MSB, val); } void SX1278Fsk::setFreqDev(int freq_dev) { uint16_t val = freq_dev / FSTEP; - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister16(REG_FDEV_MSB, val & 0x3fff); } @@ -331,13 +335,13 @@ void SX1278Fsk::setFreqRF(int freq_rf) uint32_t val = freq_rf / FSTEP; // Update values - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister24(REG_FRF_MSB, val); } void SX1278Fsk::setOcp(int ocp) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); if (ocp == 0) { spi.writeRegister(REG_OCP, 0); @@ -356,7 +360,7 @@ void SX1278Fsk::setOcp(int ocp) void SX1278Fsk::setSyncWord(uint8_t value[], int size) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister(REG_SYNC_CONFIG, REG_SYNC_CONFIG_DEFAULT | size); for (int i = 0; i < size; i++) @@ -367,19 +371,19 @@ void SX1278Fsk::setSyncWord(uint8_t value[], int size) void SX1278Fsk::setRxBw(RxBw rx_bw) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister(REG_RX_BW, static_cast<uint8_t>(rx_bw)); } void SX1278Fsk::setAfcBw(RxBw afc_bw) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister(REG_AFC_BW, static_cast<uint8_t>(afc_bw)); } void SX1278Fsk::setPreambleLen(int len) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister16(REG_PREAMBLE_MSB, len); } @@ -390,7 +394,7 @@ void SX1278Fsk::setPa(int power, bool pa_boost) const uint8_t MAX_POWER = 0b111; - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); if (!pa_boost) { @@ -408,20 +412,19 @@ void SX1278Fsk::setPa(int power, bool pa_boost) RegPaConfig::PA_SELECT_BOOST); spi.writeRegister(REG_PA_DAC, RegPaDac::PA_DAC_PA_BOOST | 0x10 << 3); } - // RA01 modules aren't capable of this, disable it to avoid damaging them - // else - // { - // // Run power amplifier boost at full power - // power = 15; - // spi.writeRegister(REG_PA_CONFIG, MAX_POWER << 4 | power | - // RegPaConfig::PA_SELECT_BOOST); - // spi.writeRegister(REG_PA_DAC, RegPaDac::PA_DAC_PA_BOOST | 0x10 << 3); - // } + else + { + // Run power amplifier boost at full power + power = 15; + spi.writeRegister(REG_PA_CONFIG, MAX_POWER << 4 | power | + RegPaConfig::PA_SELECT_BOOST); + spi.writeRegister(REG_PA_DAC, RegPaDac::PA_DAC_PA_BOOST | 0x10 << 3); + } } void SX1278Fsk::setShaping(Shaping shaping) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister(REG_PA_RAMP, static_cast<uint8_t>(shaping) | 0x09); } diff --git a/src/shared/radio/SX1278/SX1278Fsk.h b/src/shared/radio/SX1278/SX1278Fsk.h index 3b054fa95e3c6ea7dc2010031ce0a0ed3e405373..d5dfa7a5047cb62a4f00c4361cd7595d52939047 100644 --- a/src/shared/radio/SX1278/SX1278Fsk.h +++ b/src/shared/radio/SX1278/SX1278Fsk.h @@ -103,7 +103,6 @@ public: 120; //< Over current protection limit in mA (0 for no limit). int power = 10; //< Output power in dB (Between +2 and +17, or +20 for // full power). - bool pa_boost = true; //< Enable output on PA_BOOST. Shaping shaping = Shaping::GAUSSIAN_BT_1_0; //< Shaping applied to // the modulation stream. DcFree dc_free = DcFree::WHITENING; //< Dc free encoding scheme. @@ -124,8 +123,9 @@ public: * @brief Construct a new SX1278 */ explicit SX1278Fsk(SPIBus &bus, miosix::GpioPin cs, - SPI::ClockDivider clock_divider) - : SX1278Common(bus, cs, clock_divider) + SPI::ClockDivider clock_divider, + std::unique_ptr<SX1278::ISX1278Frontend> frontend) + : SX1278Common(bus, cs, clock_divider, std::move(frontend)) { } @@ -179,13 +179,6 @@ public: */ float getLastRxFei(); -protected: - // Stuff to work with various front-ends - virtual void enableRxFrontend() override {} - virtual void disableRxFrontend() override {} - virtual void enableTxFrontend() override {} - virtual void disableTxFrontend() override {} - private: void rateLimitTx(); diff --git a/src/shared/radio/SX1278/SX1278Lora.cpp b/src/shared/radio/SX1278/SX1278Lora.cpp index 60958050f28441249886a2774802be514bc33e92..0c16afd10309610fca2f7d4b370d4553d2f84b4a 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 spi(getSpiSlave()); return spi.readRegister(REG_VERSION) == 0x12; } @@ -174,8 +174,8 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config) int freq_rf = config.freq_rf; int ocp = config.ocp; - int power = config.power; - bool pa_boost = config.pa_boost; + int power = std::min(config.power, getFrontend().maxInPower()); + bool pa_boost = getFrontend().isOnPaBoost(); bool low_data_rate_optimize = config.low_data_rate_optimize; @@ -188,7 +188,7 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config) ErrataRegistersValues::calculate(bw, freq_rf); { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); // Setup FIFO sections spi.writeRegister(REG_FIFO_TX_BASE_ADDR, FIFO_TX_BASE_ADDR); @@ -275,7 +275,7 @@ ssize_t SX1278Lora::receive(uint8_t *pkt, size_t max_len) { Lock guard(*this); - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); do { @@ -303,7 +303,7 @@ bool SX1278Lora::send(uint8_t *pkt, size_t len) Lock guard(*this); - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister(REG_PAYLOAD_LENGTH, len); writeFifo(FIFO_TX_BASE_ADDR, pkt, len); @@ -325,7 +325,7 @@ float SX1278Lora::getLastRxRssi() float rssi; { Lock guard(*this); - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); rssi = static_cast<float>(spi.readRegister(REG_PKT_RSSI_VALUE)) - 164.0f; } @@ -341,7 +341,7 @@ float SX1278Lora::getLastRxRssi() float SX1278Lora::getLastRxSnr() { Lock guard(*this); - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); return static_cast<float>( static_cast<int8_t>(spi.readRegister(REG_PKT_SNR_VALUE))) / 4.0f; @@ -349,14 +349,14 @@ float SX1278Lora::getLastRxSnr() void SX1278Lora::readFifo(uint8_t addr, uint8_t *dst, uint8_t size) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); 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 spi(getSpiSlave()); spi.writeRegister(REG_FIFO_ADDR_PTR, addr); spi.writeRegisters(REG_FIFO, src, size); } @@ -391,20 +391,20 @@ SX1278::DioMask SX1278Lora::getDioMaskFromIrqFlags(IrqFlags flags, Mode _mode, ISX1278::IrqFlags SX1278Lora::getIrqFlags() { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); return spi.readRegister(REG_IRQ_FLAGS); } void SX1278Lora::resetIrqFlags(IrqFlags flags) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); // Register is write clear spi.writeRegister(REG_IRQ_FLAGS, flags); } void SX1278Lora::setMode(ISX1278::Mode mode) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister( REG_OP_MODE, @@ -413,7 +413,7 @@ void SX1278Lora::setMode(ISX1278::Mode mode) void SX1278Lora::setMapping(SX1278::DioMapping mapping) { - SPITransaction spi(slave); + SPITransaction spi(getSpiSlave()); spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw); } diff --git a/src/shared/radio/SX1278/SX1278Lora.h b/src/shared/radio/SX1278/SX1278Lora.h index f7d562bbcc5ed0a0b80b98edd38ef04651b6e652..50545de5f1980938ce0753749661cbb9b7d99c25 100644 --- a/src/shared/radio/SX1278/SX1278Lora.h +++ b/src/shared/radio/SX1278/SX1278Lora.h @@ -105,7 +105,6 @@ public: 15; //< Output power in dB (between +2 and +17 with pa_boost = on, // and between +0 and +14 with pa_boost = off, +20 for +20dBm // max power ignoring pa_boost). - bool pa_boost = true; //< Enable output on PA_BOOST. /** * @brief Calculates effective and usable bitrate. @@ -137,8 +136,9 @@ public: * @brief Construct a new SX1278 */ explicit SX1278Lora(SPIBus &bus, miosix::GpioPin cs, - SPI::ClockDivider clock_divider) - : SX1278Common(bus, cs, clock_divider) + SPI::ClockDivider clock_divider, + std::unique_ptr<SX1278::ISX1278Frontend> frontend) + : SX1278Common(bus, cs, clock_divider, std::move(frontend)) { } @@ -187,13 +187,6 @@ public: */ float getLastRxSnr(); -protected: - // Stuff to work with various front-ends - virtual void enableRxFrontend() override {} - virtual void disableRxFrontend() override {} - virtual void enableTxFrontend() override {} - virtual void disableTxFrontend() override {} - private: void readFifo(uint8_t addr, uint8_t *dst, uint8_t size); void writeFifo(uint8_t addr, uint8_t *src, uint8_t size); 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 5facf054cee370b5a43d7b2ab80717cb5e3eed80..a9aa947d30b1c9ca3ad5fe89cc2b7023d412a971 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp @@ -21,6 +21,7 @@ */ #include <drivers/interrupt/external_interrupts.h> +#include <radio/SX1278/SX1278Frontends.h> #include <radio/SX1278/SX1278Fsk.h> #include <thread> @@ -124,7 +125,9 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - sx1278 = new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64); + std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); + + sx1278 = new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); 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 9a1ad3f8ad7830e6ab2266fdcf6822d4fcb46b9a..4d679eaef4205bbbbf460da6421f47d54306b16b 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp @@ -21,6 +21,7 @@ */ #include <drivers/interrupt/external_interrupts.h> +#include <radio/SX1278/SX1278Frontends.h> #include <radio/SX1278/SX1278Fsk.h> #include <thread> @@ -116,7 +117,10 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - sx1278 = new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64); + std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); + + sx1278 = + new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); 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 6c9c47e915029e17f4bf46d1fbfdc25065a19146..91ea184399bc0400d659d0e469344effe988e332 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp @@ -22,7 +22,7 @@ #include <drivers/interrupt/external_interrupts.h> #include <miosix.h> -#include <radio/SX1278/Ebyte.h> +#include <radio/SX1278/SX1278Frontends.h> #include <radio/SX1278/SX1278Fsk.h> #include <cstring> @@ -141,7 +141,10 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - sx1278 = new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64); + std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); + + sx1278 = + new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); 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 01ba90c63de9aa33c815c1bd29fd999deab6a0ff..17d51d4b88ebf66b14a236888624d3fdf23703de 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp @@ -21,6 +21,7 @@ */ #include <drivers/interrupt/external_interrupts.h> +#include <radio/SX1278/SX1278Frontends.h> #include <radio/SX1278/SX1278Fsk.h> #include <thread> @@ -161,7 +162,10 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - sx1278 = new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64); + std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); + + sx1278 = + new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); 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 3a96bc45740fb3b3497eb37ced0aa4039131a0dd..285828cac2be3af4a563bfa60f9271977ca47e52 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp @@ -22,7 +22,7 @@ #include <drivers/interrupt/external_interrupts.h> #include <miosix.h> -#include <radio/SX1278/Ebyte.h> +#include <radio/SX1278/SX1278Frontends.h> #include <radio/SX1278/SX1278Lora.h> #include <cstring> @@ -174,7 +174,6 @@ int main() initBoard(); SX1278Lora::Config config = {}; - config.pa_boost = true; config.power = 10; config.ocp = 0; config.coding_rate = SX1278Lora::Config::Cr::CR_4; @@ -186,12 +185,15 @@ int main() GpioPin cs = cs::getPin(); #ifdef IS_EBYTE - sx1278 = new EbyteLora(bus, cs, SPI::ClockDivider::DIV_64, txen::getPin(), - rxen::getPin()); + std::unique_ptr<SX1278::ISX1278Frontend> frontend( + new EbyteFrontend(txen::getPin(), rxen::getPin())); #else - sx1278 = new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64); + std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); #endif + sx1278 = + new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE) { diff --git a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp index 8d30102caec14b0fe066ba9af9a6898076c0f78c..ce217cb63cb6ad397b074b9d1159e6fceedfab2e 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp @@ -21,6 +21,7 @@ */ #include <drivers/interrupt/external_interrupts.h> +#include <radio/SX1278/SX1278Frontends.h> #include <radio/SX1278/SX1278Lora.h> #include <thread> @@ -181,7 +182,6 @@ int main() initBoard(); SX1278Lora::Config config = {}; - config.pa_boost = true; config.power = 15; config.ocp = 0; config.coding_rate = SX1278Lora::Config::Cr::CR_1; @@ -196,12 +196,15 @@ int main() GpioPin cs = cs::getPin(); #ifdef IS_EBYTE - sx1278 = new EbyteLora(bus, cs, SPI::ClockDivider::DIV_64, txen::getPin(), - rxen::getPin()); + std::unique_ptr<SX1278::ISX1278Frontend> frontend( + new EbyteFrontend(txen::getPin(), rxen::getPin())); #else - sx1278 = new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64); + std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); #endif + sx1278 = + new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE) { diff --git a/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp b/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp index 9d19c6cecffeb38a663bc5646dac4911c4bb4e13..a651765e0d6fd5d5066efbe4a33b6cbad3408ac7 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp @@ -21,7 +21,7 @@ */ #include <drivers/interrupt/external_interrupts.h> -#include <radio/SX1278/Ebyte.h> +#include <radio/SX1278/SX1278Frontends.h> #include <radio/SX1278/SX1278Lora.h> using namespace Boardcore; @@ -104,7 +104,6 @@ int main() initBoard(); SX1278Lora::Config config = {}; - config.pa_boost = true; config.power = 10; config.ocp = 0; config.coding_rate = SX1278Lora::Config::Cr::CR_1; @@ -115,16 +114,16 @@ int main() SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); - SPIBus bus(SX1278_SPI); - GpioPin cs = cs::getPin(); - #ifdef IS_EBYTE - sx1278 = new EbyteLora(bus, cs, SPI::ClockDivider::DIV_64, txen::getPin(), - rxen::getPin()); + std::unique_ptr<SX1278::ISX1278Frontend> frontend( + new EbyteFrontend(txen::getPin(), rxen::getPin())); #else - sx1278 = new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64); + std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); #endif + sx1278 = + new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE) {