diff --git a/src/shared/radio/SX1278/SX1278Common.h b/src/shared/radio/SX1278/SX1278Common.h index 7471e0bc2c630deb93087cf461e54d71223c9396..35823c82dd0485675e99132332c16a538a05dcfb 100644 --- a/src/shared/radio/SX1278/SX1278Common.h +++ b/src/shared/radio/SX1278/SX1278Common.h @@ -132,8 +132,9 @@ public: protected: explicit SX1278Common(SPIBus &bus, miosix::GpioPin cs, SPI::ClockDivider clock_divider, - std::unique_ptr<ISX1278Frontend>) - : slave(SPISlave(bus, cs, getSpiBusConfig(clock_divider))) + std::unique_ptr<ISX1278Frontend> frontend) + : slave(SPISlave(bus, cs, getSpiBusConfig(clock_divider))), + frontend(std::move(frontend)) { } @@ -217,8 +218,8 @@ private: miosix::FastMutex mutex; DeviceState state; - std::unique_ptr<ISX1278Frontend> frontend; SPISlave slave; + std::unique_ptr<ISX1278Frontend> frontend; }; } // namespace SX1278 diff --git a/src/shared/radio/SX1278/SX1278Defs.h b/src/shared/radio/SX1278/SX1278Defs.h index 12701d83d5526db55cec4de0ca15551cb0bbd3b4..67b3652c5e9470dfd5cc24550def8173256f52fc 100644 --- a/src/shared/radio/SX1278/SX1278Defs.h +++ b/src/shared/radio/SX1278/SX1278Defs.h @@ -134,20 +134,12 @@ constexpr int FIFO_LEN = 64; namespace RegOpMode { -enum LongRangeMode -{ - LONG_RANGE_MODE_FSK = 0 << 7, - LONG_RANGE_MODE_LORA = 1 << 7 -}; - enum ModulationType { MODULATION_TYPE_FSK = 0 << 6, MODULATION_TYPE_OOK = 1 << 6, }; -constexpr uint8_t LOW_FREQUENCY_MODE_ON = 1 << 3; - enum Mode { MODE_SLEEP = 0b000, @@ -158,94 +150,197 @@ enum Mode MODE_RX = 0b101, }; +inline constexpr uint8_t make(Mode mode, bool low_frequency_mode_on, + ModulationType modulation_type) +{ + return mode | (low_frequency_mode_on ? (1 << 3) : 0) | + (modulation_type << 5); +} + } // namespace RegOpMode namespace RegPaConfig { -constexpr uint8_t PA_SELECT_BOOST = 1 << 7; + +inline constexpr uint8_t make(uint8_t output_power, uint8_t max_power, + bool pa_select) +{ + return (output_power & 0b1111) | ((max_power & 0b111) << 4) | + (pa_select ? 1 << 7 : 0); +} + } namespace RegPaRamp { enum ModulationShaping { - MODULATION_SHAPING_NONE = 0b00 << 5, - MODULATION_SHAPING_GAUSSIAN_BT_1_0 = 0b01 << 5, - MODULATION_SHAPING_GAUSSIAN_BT_0_5 = 0b10 << 5, - MODULATION_SHAPING_GAUSSIAN_BT_0_3 = 0b11 << 5, + MODULATION_SHAPING_NONE = 0b00, + MODULATION_SHAPING_GAUSSIAN_BT_1_0 = 0b01, + MODULATION_SHAPING_GAUSSIAN_BT_0_5 = 0b10, + MODULATION_SHAPING_GAUSSIAN_BT_0_3 = 0b11, }; + +enum PaRamp +{ + PA_RAMP_MS_3_4 = 0b0000, + PA_RAMP_MS_2 = 0b0001, + PA_RAMP_MS_1 = 0b0010, + PA_RAMP_US_500 = 0b0011, + PA_RAMP_US_250 = 0b0100, + PA_RAMP_US_125 = 0b0101, + PA_RAMP_US_100 = 0b0110, + PA_RAMP_US_62 = 0b0111, + PA_RAMP_US_50 = 0b1000, + PA_RAMP_US_40 = 0b1001, + PA_RAMP_US_31 = 0b1010, + PA_RAMP_US_25 = 0b1011, + PA_RAMP_US_20 = 0b1100, + PA_RAMP_US_15 = 0b1101, + PA_RAMP_US_12 = 0b1110, + PA_RAMP_US_10 = 0b1111, +}; + +inline constexpr uint8_t make(PaRamp pa_ramp, + ModulationShaping modulation_shaping) +{ + return pa_ramp | (modulation_shaping << 5); +} + } namespace RegOcp { -constexpr uint8_t OCP_ON = 1 << 5; + +inline constexpr uint8_t make(uint8_t ocp_trim, bool ocp_on) +{ + return (ocp_trim & 0b11111) | (ocp_on ? 1 << 5 : 0); +} + } namespace RegRxConfig { -constexpr uint8_t RESTART_RX_ON_COLLISION = 1 << 7; -constexpr uint8_t RESTART_RX_WITHOUT_PILL_LOCK = 1 << 6; -constexpr uint8_t RESTART_RX_WITH_PILL_LOCK = 1 << 5; -constexpr uint8_t AFC_AUTO_ON = 1 << 4; -constexpr uint8_t AGC_AUTO_ON = 1 << 3; -constexpr uint8_t RX_TRIGGER_RSSI_INTERRUPT = 0b001; -constexpr uint8_t RX_TRIGGER_PREAMBLE_DETECT = 0b110; +inline constexpr uint8_t make(bool rx_trigger_rssi_interrupt, + bool rx_trigger_preable_detect, bool agc_auto_on, + bool afc_auto_on, bool restart_rx_with_pll_lock, + bool restart_rx_without_pll_lock, + bool restart_rx_on_collision) +{ + return (rx_trigger_rssi_interrupt ? 0b001 : 0) | + (rx_trigger_preable_detect ? 0b110 << 1 : 0) | + (agc_auto_on ? 1 << 3 : 0) | (afc_auto_on ? 1 << 4 : 0) | + (restart_rx_with_pll_lock ? 1 << 5 : 0) | + (restart_rx_without_pll_lock ? 1 << 6 : 0) | + (restart_rx_on_collision ? 1 << 7 : 0); +} + } // namespace RegRxConfig +namespace RegRxBw +{ + +enum RxBw +{ + HZ_2600 = 0b10111, + HZ_3100 = 0b01111, + HZ_3900 = 0b00111, + HZ_5200 = 0b10110, + HZ_6300 = 0b01110, + HZ_7800 = 0b00110, + HZ_10400 = 0b10101, + HZ_12500 = 0b01101, + HZ_15600 = 0b00101, + HZ_20800 = 0b10100, + HZ_25000 = 0b01100, + HZ_31300 = 0b00100, + HZ_41700 = 0b10011, + HZ_50000 = 0b01011, + HZ_62500 = 0b00011, + HZ_83300 = 0b10010, + HZ_100000 = 0b01010, + HZ_125000 = 0b00010, + HZ_166700 = 0b10001, + HZ_200000 = 0b01001, + HZ_250000 = 0b00001, +}; + +inline constexpr uint8_t make(RxBw rx_bw) { return rx_bw; } + +} + +namespace RegAfcBw +{ + +using RxBwAfc = Boardcore::SX1278::Fsk::RegRxBw::RxBw; + +inline constexpr uint8_t make(RxBwAfc rx_bw_afc) { return rx_bw_afc; } + +} + namespace RegPreambleDetector { -constexpr uint8_t PREAMBLE_DETECTOR_ON = 1 << 7; -enum PreambleDetectorSize +enum Size { - PREAMBLE_DETECTOR_SIZE_1_BYTE = 0b00 << 5, - PREAMBLE_DETECTOR_SIZE_2_BYTES = 0b01 << 5, - PREAMBLE_DETECTOR_SIZE_3_BYTES = 0b10 << 5, + PREAMBLE_DETECTOR_SIZE_1_BYTE = 0b00, + PREAMBLE_DETECTOR_SIZE_2_BYTES = 0b01, + PREAMBLE_DETECTOR_SIZE_3_BYTES = 0b10, }; + +inline constexpr uint8_t make(int tol, Size size, bool on) +{ + return (tol & 0b11111) | (size << 5) | (on ? 1 << 7 : 0); +} + } // namespace RegPreambleDetector namespace RegSyncConfig { enum AutoRestartRxMode { - AUTO_RESTART_RX_MODE_OFF = 0b00 << 6, - AUTO_RESTART_RX_MODE_ON_WITHOUT_PILL_LOCK = 0b01 << 6, - AUTO_RESTART_RX_MODE_ON_WITH_PILL_LOCK = 0b10 << 6, + AUTO_RESTART_RX_MODE_OFF = 0b00, + AUTO_RESTART_RX_MODE_ON_WITHOUT_PILL_LOCK = 0b01, + AUTO_RESTART_RX_MODE_ON_WITH_PILL_LOCK = 0b10, }; enum PreamblePolarity { - PREAMBLE_POLARITY_AA = 0 << 5, - PREAMBLE_POLARITY_55 = 1 << 5, + PREAMBLE_POLARITY_AA = 0, + PREAMBLE_POLARITY_55 = 1, }; -constexpr uint8_t SYNC_ON = 1 << 4; +inline constexpr uint8_t make(int size, bool on, + PreamblePolarity preamble_polarity, + AutoRestartRxMode auto_restart_rx_mode) +{ + return ((size - 1) & 0b111) | (on ? 1 << 4 : 0) | (preamble_polarity << 5) | + (auto_restart_rx_mode << 6); +} + } // namespace RegSyncConfig namespace RegPacketConfig1 { enum PacketFormat { - PACKET_FORMAT_FIXED_LENGTH = 0 << 7, - PACKET_FORMAT_VARIABLE_LENGTH = 1 << 7, + PACKET_FORMAT_FIXED_LENGTH = 0, + PACKET_FORMAT_VARIABLE_LENGTH = 1, }; enum DcFree { - DC_FREE_NONE = 0b00 << 5, - DC_FREE_MANCHESTER = 0b01 << 5, - DC_FREE_WHITENING = 0b10 << 5, + DC_FREE_NONE = 0b00, + DC_FREE_MANCHESTER = 0b01, + DC_FREE_WHITENING = 0b10, }; -constexpr uint8_t CRC_ON = 1 << 4; -constexpr uint8_t CRC_AUTO_CLEAR_OFF = 1 << 3; - enum AddressFiltering { - ADDRESS_FILTERING_NONE = 0b00 << 1, - ADDRESS_FILTERING_MATCH_NODE = 0b01 << 1, - ADDRESS_FILTERING_MATCH_NODE_OR_BROADCAST = 0b10 << 1, + ADDRESS_FILTERING_NONE = 0b00, + ADDRESS_FILTERING_MATCH_NODE = 0b01, + ADDRESS_FILTERING_MATCH_NODE_OR_BROADCAST = 0b10, }; enum CrcWhiteningType @@ -253,27 +348,50 @@ enum CrcWhiteningType CRC_WHITENING_TYPE_CCITT_CRC = 0, CRC_WHITENING_TYPE_IBM_CRC = 1, }; + +inline constexpr uint8_t make(CrcWhiteningType crc_whitening_type, + AddressFiltering address_filtering, + bool crc_auto_clear_off, bool crc_on, + DcFree dc_free, PacketFormat packet_format) +{ + return crc_whitening_type | (address_filtering << 1) | + (crc_auto_clear_off ? 1 << 3 : 0) | (crc_on ? 1 << 4 : 0) | + (dc_free << 5) | (packet_format << 7); +} + } // namespace RegPacketConfig1 namespace RegPacketConfig2 { enum DataMode { - DATA_MODE_CONTINUOS = 0 << 6, - DATA_MODE_PACKET = 1 << 6 + DATA_MODE_CONTINUOS = 0, + DATA_MODE_PACKET = 1 }; -constexpr uint8_t IO_HOME_ON = 1 << 5; -constexpr uint8_t BEACON_ON = 1 << 4; +inline constexpr uint8_t make(bool beacon_on, bool io_home_power_frame, + bool io_home_on, DataMode data_mode) +{ + return (beacon_on ? 1 << 3 : 0) | (io_home_power_frame ? 1 << 4 : 0) | + (io_home_on ? 1 << 5 : 0) | (data_mode << 6); +} + } // namespace RegPacketConfig2 namespace RegFifoThresh { enum TxStartCondition { - TX_START_CONDITION_FIFO_LEVEL = 0 << 7, - TX_START_CONDITION_FIFO_NOT_EMPTY = 1 << 7, + TX_START_CONDITION_FIFO_LEVEL = 0, + TX_START_CONDITION_FIFO_NOT_EMPTY = 1, }; + +inline constexpr uint8_t make(int fifo_threshold, + TxStartCondition tx_start_condition) +{ + return (fifo_threshold & 0b111111) | (tx_start_condition << 7); +} + } namespace RegIrqFlags @@ -308,22 +426,10 @@ enum PaDac PA_DAC_DEFAULT_VALUE = 0x04, PA_DAC_PA_BOOST = 0x07 }; -} - -namespace RegImageCal -{ -constexpr uint8_t AUTO_IMAGE_CAL_ON = 0x80; -enum TempThreshold -{ - TEMP_THRESHOLD_5DEG = 0x00, - TEMP_THRESHOLD_10DEG = 0x02, - TEMP_THRESHOLD_15DEG = 0x04, - TEMP_THRESHOLD_20DEG = 0x06, -}; +inline constexpr uint8_t make(PaDac pa_dac) { return pa_dac | (0x10 << 3); } -constexpr uint8_t TEMP_MONITOR_OFF = 0x01; -} // namespace RegImageCal +} enum Registers { diff --git a/src/shared/radio/SX1278/SX1278Frontends.h b/src/shared/radio/SX1278/SX1278Frontends.h index ea87ed44cad3c9008e27c2b7dd7cc5ec841638e0..eb8db2e3640a182551fd095747b3632978cb8d49 100644 --- a/src/shared/radio/SX1278/SX1278Frontends.h +++ b/src/shared/radio/SX1278/SX1278Frontends.h @@ -58,6 +58,8 @@ private: class RA01Frontend : public SX1278::ISX1278Frontend { public: + RA01Frontend() {} + bool isOnPaBoost() override { return true; } int maxInPower() override { return 17; } diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp index f074edeb530f73d1b17c786ea121b160d4ebb1c4..087b79b3e6ceb6a80427da09a8cd225c16578fe8 100644 --- a/src/shared/radio/SX1278/SX1278Fsk.cpp +++ b/src/shared/radio/SX1278/SX1278Fsk.cpp @@ -35,17 +35,6 @@ using namespace SX1278::Fsk; long long now() { return miosix::getTick() * 1000 / miosix::TICK_FREQ; } -// Default values for registers -constexpr uint8_t REG_OP_MODE_DEFAULT = RegOpMode::LONG_RANGE_MODE_FSK | - RegOpMode::MODULATION_TYPE_FSK | - RegOpMode::LOW_FREQUENCY_MODE_ON; - -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_THRESHOLD_10DEG; - // Enable: // - PayloadReady, PacketSent on DIO0 (mode 00) // - FifoLevel on DIO1 (mode 00) @@ -91,57 +80,135 @@ SX1278Fsk::Error SX1278Fsk::configure(const Config &config) if (!waitForIrqBusy(guard_mode, RegIrqFlags::MODE_READY, 1000)) return Error::IRQ_TIMEOUT; - setBitrate(config.bitrate); - setFreqDev(config.freq_dev); - setFreqRF(config.freq_rf); - - setRxBw(config.rx_bw); - setAfcBw(config.afc_bw); - - setOcp(config.ocp); - - uint8_t sync_word[2] = {0x12, 0xad}; - setSyncWord(sync_word, 2); - setPreambleLen(2); - setShaping(config.shaping); - - // Make sure the PA matches settings with the frontend + int bitrate = config.bitrate; + int freq_dev = config.freq_dev; + int freq_rf = config.freq_rf; + RegRxBw::RxBw rx_bw = static_cast<RegRxBw::RxBw>(config.rx_bw); + RegAfcBw::RxBwAfc afc_bw = static_cast<RegAfcBw::RxBwAfc>(config.afc_bw); + int ocp = config.ocp; int power = std::min(config.power, getFrontend().maxInPower()); bool pa_boost = getFrontend().isOnPaBoost(); - setPa(power, pa_boost); + RegPaRamp::ModulationShaping shaping = + static_cast<RegPaRamp::ModulationShaping>(config.shaping); + RegPacketConfig1::DcFree dc_free = + static_cast<RegPacketConfig1::DcFree>(config.dc_free); - // Setup generic parameters { SPITransaction spi(getSpiSlave()); - spi.writeRegister(REG_RX_CONFIG, - RegRxConfig::AFC_AUTO_ON | RegRxConfig::AGC_AUTO_ON | - RegRxConfig::RX_TRIGGER_PREAMBLE_DETECT | - RegRxConfig::RX_TRIGGER_RSSI_INTERRUPT); + // Setup bitrate + uint16_t bitrate_val = FXOSC / bitrate; + spi.writeRegister16(REG_BITRATE_MSB, bitrate_val); + + // Setup frequency deviation + uint16_t freq_dev_raw = freq_dev / FSTEP; + spi.writeRegister16(REG_FDEV_MSB, freq_dev_raw & 0x3fff); + + // Setup base frequency + uint32_t freq_rf_raw = freq_rf / FSTEP; + spi.writeRegister24(REG_FRF_MSB, freq_rf_raw); + + // Setup RX bandwidth + spi.writeRegister(REG_RX_BW, RegRxBw::make(rx_bw)); + + // Setup afc bandwidth + spi.writeRegister(REG_AFC_BW, RegAfcBw::make(afc_bw)); + + // Setup reg over-current protection + if (config.ocp == 0) + { + spi.writeRegister(REG_OCP, RegOcp::make(0, false)); + } + else if (ocp <= 120) + { + spi.writeRegister(REG_OCP, RegOcp::make((ocp - 45) / 5, true)); + } + else + { + spi.writeRegister(REG_OCP, RegOcp::make((ocp + 30) / 10, true)); + } + + // Setup sync word + spi.writeRegister( + REG_SYNC_CONFIG, + RegSyncConfig::make(2, true, RegSyncConfig::PREAMBLE_POLARITY_55, + RegSyncConfig::AUTO_RESTART_RX_MODE_OFF)); + spi.writeRegister(REG_SYNC_VALUE_1, 0x12); + spi.writeRegister(REG_SYNC_VALUE_2, 0xad); + + // Setup shaping + spi.writeRegister(REG_PA_RAMP, + RegPaRamp::make(RegPaRamp::PA_RAMP_US_40, shaping)); + + // Setup power amplifier + // [2, 17] or 20 if PA_BOOST + // [0, 15] if !PA_BOOST + const int MAX_POWER = 0b111; + if (!pa_boost) + { + // Don't use power amplifier boost + spi.writeRegister(REG_PA_CONFIG, + RegPaConfig::make(power, MAX_POWER, false)); + spi.writeRegister(REG_PA_DAC, + RegPaDac::make(RegPaDac::PA_DAC_DEFAULT_VALUE)); + } + else if (power != 20) + { + // Run power amplifier boost but not at full power + spi.writeRegister(REG_PA_CONFIG, + RegPaConfig::make(power - 2, MAX_POWER, true)); + spi.writeRegister(REG_PA_DAC, + RegPaDac::make(RegPaDac::PA_DAC_PA_BOOST)); + } + else + { + // Run power amplifier boost at full power + spi.writeRegister(REG_PA_CONFIG, + RegPaConfig::make(0b1111, MAX_POWER, true)); + spi.writeRegister(REG_PA_DAC, + RegPaDac::make(RegPaDac::PA_DAC_PA_BOOST)); + } + + // Setup other registers + spi.writeRegister16(REG_PREAMBLE_MSB, 2); + + spi.writeRegister( + REG_RX_CONFIG, + RegRxConfig::make(true, true, true, true, false, false, false)); + spi.writeRegister(REG_RSSI_THRESH, 0xff); + spi.writeRegister( REG_PREAMBLE_DETECT, - RegPreambleDetector::PREAMBLE_DETECTOR_ON | - RegPreambleDetector::PREAMBLE_DETECTOR_SIZE_2_BYTES | 0x0a); + RegPreambleDetector::make( + 0x0a, RegPreambleDetector::PREAMBLE_DETECTOR_SIZE_2_BYTES, + true)); + spi.writeRegister(REG_RX_TIMEOUT_1, 0x00); spi.writeRegister(REG_RX_TIMEOUT_2, 0x00); spi.writeRegister(REG_RX_TIMEOUT_3, 0x00); - spi.writeRegister(REG_PACKET_CONFIG_1, - RegPacketConfig1::PACKET_FORMAT_VARIABLE_LENGTH | - static_cast<uint8_t>(config.dc_free) | - RegPacketConfig1::CRC_ON | - RegPacketConfig1::ADDRESS_FILTERING_NONE | - RegPacketConfig1::CRC_WHITENING_TYPE_CCITT_CRC); - spi.writeRegister(REG_PACKET_CONFIG_2, - RegPacketConfig2::DATA_MODE_PACKET); + + spi.writeRegister( + REG_PACKET_CONFIG_1, + RegPacketConfig1::make( + RegPacketConfig1::CRC_WHITENING_TYPE_CCITT_CRC, + RegPacketConfig1::ADDRESS_FILTERING_NONE, false, true, dc_free, + RegPacketConfig1::PACKET_FORMAT_VARIABLE_LENGTH)); + + spi.writeRegister( + REG_PACKET_CONFIG_2, + RegPacketConfig2::make(false, false, false, + RegPacketConfig2::DATA_MODE_PACKET)); + spi.writeRegister( REG_FIFO_THRESH, - RegFifoThresh::TX_START_CONDITION_FIFO_NOT_EMPTY | 0x0f); + RegFifoThresh::make( + 0x0f, RegFifoThresh::TX_START_CONDITION_FIFO_NOT_EMPTY)); + spi.writeRegister(REG_NODE_ADRS, 0x00); spi.writeRegister(REG_BROADCAST_ADRS, 0x00); } - // imageCalibrate(); return Error::NONE; } @@ -228,16 +295,6 @@ void SX1278Fsk::rateLimitTx() } } -void SX1278Fsk::imageCalibrate() -{ - SPITransaction spi(getSpiSlave()); - spi.writeRegister(REG_IMAGE_CAL, REG_IMAGE_CAL_DEFAULT | (1 << 6)); - - // Wait for calibration complete by polling on running register - while (spi.readRegister(REG_IMAGE_CAL) & (1 << 5)) - miosix::delayUs(10); -} - DioMask SX1278Fsk::getDioMaskFromIrqFlags(IrqFlags flags, Mode mode, DioMapping mapping) { @@ -289,7 +346,6 @@ float SX1278Fsk::getRssi() SPITransaction spi(getSpiSlave()); uint8_t rssi_raw = spi.readRegister(REG_RSSI_VALUE); - return static_cast<float>(rssi_raw) * -0.5f; } @@ -298,14 +354,15 @@ float SX1278Fsk::getFei() SPITransaction spi(getSpiSlave()); uint16_t fei_raw = spi.readRegister16(REG_FEI_MSB); - return static_cast<float>(fei_raw) * FSTEP; } void SX1278Fsk::setMode(Mode mode) { SPITransaction spi(getSpiSlave()); - spi.writeRegister(REG_OP_MODE, REG_OP_MODE_DEFAULT | mode); + spi.writeRegister(REG_OP_MODE, + RegOpMode::make(static_cast<RegOpMode::Mode>(mode), true, + RegOpMode::MODULATION_TYPE_FSK)); } void SX1278Fsk::setMapping(SX1278::DioMapping mapping) @@ -314,118 +371,4 @@ void SX1278Fsk::setMapping(SX1278::DioMapping mapping) spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw); } -void SX1278Fsk::setBitrate(int bitrate) -{ - uint16_t val = FXOSC / bitrate; - - // Update values - SPITransaction spi(getSpiSlave()); - spi.writeRegister16(REG_BITRATE_MSB, val); -} - -void SX1278Fsk::setFreqDev(int freq_dev) -{ - uint16_t val = freq_dev / FSTEP; - SPITransaction spi(getSpiSlave()); - spi.writeRegister16(REG_FDEV_MSB, val & 0x3fff); -} - -void SX1278Fsk::setFreqRF(int freq_rf) -{ - uint32_t val = freq_rf / FSTEP; - - // Update values - SPITransaction spi(getSpiSlave()); - spi.writeRegister24(REG_FRF_MSB, val); -} - -void SX1278Fsk::setOcp(int ocp) -{ - SPITransaction spi(getSpiSlave()); - if (ocp == 0) - { - spi.writeRegister(REG_OCP, 0); - } - else if (ocp <= 120) - { - uint8_t raw = (ocp - 45) / 5; - spi.writeRegister(REG_OCP, RegOcp::OCP_ON | raw); - } - else - { - uint8_t raw = (ocp + 30) / 10; - spi.writeRegister(REG_OCP, RegOcp::OCP_ON | raw); - } -} - -void SX1278Fsk::setSyncWord(uint8_t value[], int size) -{ - SPITransaction spi(getSpiSlave()); - spi.writeRegister(REG_SYNC_CONFIG, REG_SYNC_CONFIG_DEFAULT | size); - - for (int i = 0; i < size; i++) - { - spi.writeRegister(REG_SYNC_VALUE_1 + i, value[i]); - } -} - -void SX1278Fsk::setRxBw(RxBw rx_bw) -{ - SPITransaction spi(getSpiSlave()); - spi.writeRegister(REG_RX_BW, static_cast<uint8_t>(rx_bw)); -} - -void SX1278Fsk::setAfcBw(RxBw afc_bw) -{ - SPITransaction spi(getSpiSlave()); - spi.writeRegister(REG_AFC_BW, static_cast<uint8_t>(afc_bw)); -} - -void SX1278Fsk::setPreambleLen(int len) -{ - SPITransaction spi(getSpiSlave()); - spi.writeRegister16(REG_PREAMBLE_MSB, len); -} - -void SX1278Fsk::setPa(int power, bool pa_boost) -{ - // [2, 17] or 20 if PA_BOOST - // [0, 15] if !PA_BOOST - - const uint8_t MAX_POWER = 0b111; - - SPITransaction spi(getSpiSlave()); - - if (!pa_boost) - { - // Don't use power amplifier boost - power = power - MAX_POWER + 15; - spi.writeRegister(REG_PA_CONFIG, MAX_POWER << 4 | power); - spi.writeRegister(REG_PA_DAC, - RegPaDac::PA_DAC_DEFAULT_VALUE | 0x10 << 3); - } - else if (power != 20) - { - // Run power amplifier boost but not at full power - power = power - 2; - 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(getSpiSlave()); - spi.writeRegister(REG_PA_RAMP, static_cast<uint8_t>(shaping) | 0x09); -} - } // namespace Boardcore diff --git a/src/shared/radio/SX1278/SX1278Fsk.h b/src/shared/radio/SX1278/SX1278Fsk.h index d5dfa7a5047cb62a4f00c4361cd7595d52939047..8210ad1d2f37702b02100d6a0081d85a3947dbd4 100644 --- a/src/shared/radio/SX1278/SX1278Fsk.h +++ b/src/shared/radio/SX1278/SX1278Fsk.h @@ -43,57 +43,69 @@ public: */ static constexpr size_t MTU = SX1278::Fsk::FIFO_LEN - 1; - /** - * @brief Channel filter bandwidth. - */ - enum class RxBw - { - HZ_2600 = (0b10 << 3) | 7, - HZ_3100 = (0b01 << 3) | 7, - HZ_3900 = 7, - HZ_5200 = (0b10 << 3) | 6, - HZ_6300 = (0b01 << 3) | 6, - HZ_7800 = 6, - HZ_10400 = (0b10 << 3) | 5, - HZ_12500 = (0b01 << 3) | 5, - HZ_15600 = 5, - HZ_20800 = (0b10 << 3) | 4, - HZ_25000 = (0b01 << 3) | 4, - HZ_31300 = 4, - HZ_41700 = (0b10 << 3) | 3, - HZ_50000 = (0b01 << 3) | 3, - HZ_62500 = 3, - HZ_83300 = (0b10 << 3) | 2, - HZ_100000 = (0b01 << 3) | 2, - HZ_125000 = 2, - HZ_166700 = (0b10 << 3) | 1, - HZ_200000 = (0b01 << 3) | 1, - HZ_250000 = 1, - }; - - enum class Shaping - { - NONE = SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_NONE, - GAUSSIAN_BT_1_0 = - SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_1_0, - GAUSSIAN_BT_0_5 = - SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_0_5, - GAUSSIAN_BT_0_3 = - SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_0_3, - }; - - enum class DcFree - { - NONE = SX1278::Fsk::RegPacketConfig1::DC_FREE_NONE, - MANCHESTER = SX1278::Fsk::RegPacketConfig1::DC_FREE_MANCHESTER, - WHITENING = SX1278::Fsk::RegPacketConfig1::DC_FREE_WHITENING - }; - /** * @brief Requested SX1278 configuration. */ struct Config { + /** + * @brief Channel filter bandwidth. + */ + enum class RxBw + { + HZ_2600 = SX1278::Fsk::RegRxBw::HZ_2600, + HZ_3100 = SX1278::Fsk::RegRxBw::HZ_3100, + HZ_3900 = SX1278::Fsk::RegRxBw::HZ_3900, + HZ_5200 = SX1278::Fsk::RegRxBw::HZ_5200, + HZ_6300 = SX1278::Fsk::RegRxBw::HZ_6300, + HZ_7800 = SX1278::Fsk::RegRxBw::HZ_7800, + HZ_10400 = SX1278::Fsk::RegRxBw::HZ_10400, + HZ_12500 = SX1278::Fsk::RegRxBw::HZ_12500, + HZ_15600 = SX1278::Fsk::RegRxBw::HZ_15600, + HZ_20800 = SX1278::Fsk::RegRxBw::HZ_20800, + HZ_25000 = SX1278::Fsk::RegRxBw::HZ_25000, + HZ_31300 = SX1278::Fsk::RegRxBw::HZ_31300, + HZ_41700 = SX1278::Fsk::RegRxBw::HZ_41700, + HZ_50000 = SX1278::Fsk::RegRxBw::HZ_50000, + HZ_62500 = SX1278::Fsk::RegRxBw::HZ_62500, + HZ_83300 = SX1278::Fsk::RegRxBw::HZ_83300, + HZ_100000 = SX1278::Fsk::RegRxBw::HZ_100000, + HZ_125000 = SX1278::Fsk::RegRxBw::HZ_125000, + HZ_166700 = SX1278::Fsk::RegRxBw::HZ_166700, + HZ_200000 = SX1278::Fsk::RegRxBw::HZ_200000, + HZ_250000 = SX1278::Fsk::RegRxBw::HZ_250000, + }; + + /** + * @brief Output modulation shaping. + */ + enum class Shaping + { + NONE = SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_NONE, + GAUSSIAN_BT_1_0 = + SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_1_0, + GAUSSIAN_BT_0_5 = + SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_0_5, + GAUSSIAN_BT_0_3 = + SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_0_3, + }; + + /** + * @brief Dc free encoding. + * + * @warning Setting this to NONE heightens the probability of long + * sequences of 0s, reducing reliability. + * + * @warning MANCHESTER might be slightly more reliable, but halves the + * bitrate. + */ + enum class DcFree + { + NONE = SX1278::Fsk::RegPacketConfig1::DC_FREE_NONE, + MANCHESTER = SX1278::Fsk::RegPacketConfig1::DC_FREE_MANCHESTER, + WHITENING = SX1278::Fsk::RegPacketConfig1::DC_FREE_WHITENING + }; + int freq_rf = 434000000; //< RF Frequency in Hz. int freq_dev = 50000; //< Frequency deviation in Hz. int bitrate = 48000; //< Bitrate in b/s. @@ -101,7 +113,7 @@ public: RxBw afc_bw = RxBw::HZ_125000; //< Afc filter bandwidth. int ocp = 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 + int power = 13; //< Output power in dB (Between +2 and +17, or +20 for // full power). Shaping shaping = Shaping::GAUSSIAN_BT_1_0; //< Shaping applied to // the modulation stream. @@ -182,8 +194,6 @@ public: private: void rateLimitTx(); - void imageCalibrate(); - SX1278::DioMask getDioMaskFromIrqFlags(IrqFlags flags, Mode mode, SX1278::DioMapping mapping) override; @@ -196,17 +206,6 @@ private: void setMode(Mode mode) override; void setMapping(SX1278::DioMapping mapping) override; - void setBitrate(int bitrate); - void setFreqDev(int freq_dev); - void setFreqRF(int freq_rf); - void setOcp(int ocp); - void setSyncWord(uint8_t value[], int size); - void setRxBw(RxBw rx_bw); - void setAfcBw(RxBw afc_bw); - void setPreambleLen(int len); - void setPa(int power, bool pa_boost); - void setShaping(Shaping shaping); - long long last_tx = 0; float last_rx_rssi = 0.0f; PrintLogger logger = Logging::getLogger("sx1278"); diff --git a/src/shared/radio/SX1278/SX1278Lora.cpp b/src/shared/radio/SX1278/SX1278Lora.cpp index 0c16afd10309610fca2f7d4b370d4553d2f84b4a..7ffa2970d76c7f2e8f8bfa1daeb965d25adbe768 100644 --- a/src/shared/radio/SX1278/SX1278Lora.cpp +++ b/src/shared/radio/SX1278/SX1278Lora.cpp @@ -197,7 +197,6 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config) // Setup frequency uint32_t freq_rf_raw = errata_values.freq_rf / FSTEP; - spi.writeRegister24(REG_FRF_MSB, freq_rf_raw); // Setup reg power amplifier diff --git a/src/shared/radio/SX1278/SX1278Lora.h b/src/shared/radio/SX1278/SX1278Lora.h index 50545de5f1980938ce0753749661cbb9b7d99c25..77994f8df0bc56e207042a4d3aacd09c7bd7518d 100644 --- a/src/shared/radio/SX1278/SX1278Lora.h +++ b/src/shared/radio/SX1278/SX1278Lora.h @@ -102,7 +102,7 @@ public: int ocp = 120; //< Over current protection limit in mA (0 for no limit). int power = - 15; //< Output power in dB (between +2 and +17 with pa_boost = on, + 13; //< 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). diff --git a/src/tests/radio/sx1278/fsk/common.h b/src/tests/radio/sx1278/fsk/common.h index d95cacd0aa3f0b79eaa3463cf821c2572b8b9146..9106da46ad3c3560e58dbe53b732dc132a9ad6c7 100644 --- a/src/tests/radio/sx1278/fsk/common.h +++ b/src/tests/radio/sx1278/fsk/common.h @@ -32,56 +32,58 @@ static const char *stringFromErr(Boardcore::SX1278Fsk::Error err) return "Error::BAD_VALUE"; case Boardcore::SX1278Fsk::Error::BAD_VERSION: return "Error::BAD_VERSION"; + case Boardcore::SX1278Fsk::Error::IRQ_TIMEOUT: + return "Error::IRQ_TIMEOUT"; default: return "<unknown>"; } } -static const char *stringFromRxBw(Boardcore::SX1278Fsk::RxBw rx_bw) +static const char *stringFromRxBw(Boardcore::SX1278Fsk::Config::RxBw rx_bw) { switch (rx_bw) { - case Boardcore::SX1278Fsk::RxBw::HZ_2600: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_2600: return "RxBw::HZ_2600"; - case Boardcore::SX1278Fsk::RxBw::HZ_3100: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_3100: return "RxBw::HZ_3100"; - case Boardcore::SX1278Fsk::RxBw::HZ_3900: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_3900: return "RxBw::HZ_3900"; - case Boardcore::SX1278Fsk::RxBw::HZ_5200: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_5200: return "RxBw::HZ_5200"; - case Boardcore::SX1278Fsk::RxBw::HZ_6300: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_6300: return "RxBw::HZ_6300"; - case Boardcore::SX1278Fsk::RxBw::HZ_7800: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_7800: return "RxBw::HZ_7800"; - case Boardcore::SX1278Fsk::RxBw::HZ_10400: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_10400: return "RxBw::HZ_10400"; - case Boardcore::SX1278Fsk::RxBw::HZ_12500: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_12500: return "RxBw::HZ_12500"; - case Boardcore::SX1278Fsk::RxBw::HZ_15600: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_15600: return "RxBw::HZ_15600"; - case Boardcore::SX1278Fsk::RxBw::HZ_20800: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_20800: return "RxBw::HZ_20800"; - case Boardcore::SX1278Fsk::RxBw::HZ_25000: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_25000: return "RxBw::HZ_25000"; - case Boardcore::SX1278Fsk::RxBw::HZ_31300: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_31300: return "RxBw::HZ_31300"; - case Boardcore::SX1278Fsk::RxBw::HZ_41700: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_41700: return "RxBw::HZ_41700"; - case Boardcore::SX1278Fsk::RxBw::HZ_50000: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_50000: return "RxBw::HZ_50000"; - case Boardcore::SX1278Fsk::RxBw::HZ_62500: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_62500: return "RxBw::HZ_62500"; - case Boardcore::SX1278Fsk::RxBw::HZ_83300: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_83300: return "RxBw::HZ_83300"; - case Boardcore::SX1278Fsk::RxBw::HZ_100000: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_100000: return "RxBw::HZ_100000"; - case Boardcore::SX1278Fsk::RxBw::HZ_125000: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_125000: return "RxBw::HZ_125000"; - case Boardcore::SX1278Fsk::RxBw::HZ_166700: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_166700: return "RxBw::HZ_166700"; - case Boardcore::SX1278Fsk::RxBw::HZ_200000: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_200000: return "RxBw::HZ_200000"; - case Boardcore::SX1278Fsk::RxBw::HZ_250000: + case Boardcore::SX1278Fsk::Config::RxBw::HZ_250000: return "RxBw::HZ_250000"; default: return "<unknown>"; 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 a9aa947d30b1c9ca3ad5fe89cc2b7023d412a971..e098f4150c7b529c1fc8d2139af025d653d2bc6f 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp @@ -114,20 +114,21 @@ int main() .freq_rf = 422075000, .freq_dev = 25000, .bitrate = 19200, - .rx_bw = Boardcore::SX1278Fsk::RxBw::HZ_83300, - .afc_bw = Boardcore::SX1278Fsk::RxBw::HZ_125000, + .rx_bw = SX1278Fsk::Config::RxBw::HZ_83300, + .afc_bw = SX1278Fsk::Config::RxBw::HZ_125000, .ocp = 120, .power = 17, - .shaping = Boardcore::SX1278Fsk::Shaping::GAUSSIAN_BT_1_0, - .dc_free = Boardcore::SX1278Fsk::DcFree::WHITENING}; + .shaping = SX1278Fsk::Config::Shaping::GAUSSIAN_BT_1_0, + .dc_free = SX1278Fsk::Config::DcFree::WHITENING}; SX1278Fsk::Error err; SPIBus bus(SX1278_SPI); GpioPin cs = cs::getPin(); std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); - - sx1278 = new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + + 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 4d679eaef4205bbbbf460da6421f47d54306b16b..5d00127ed66464bf9a3dc141d3469c6444f393db 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp @@ -106,12 +106,12 @@ int main() .freq_rf = 422075000, .freq_dev = 25000, .bitrate = 19200, - .rx_bw = Boardcore::SX1278Fsk::RxBw::HZ_83300, - .afc_bw = Boardcore::SX1278Fsk::RxBw::HZ_125000, + .rx_bw = SX1278Fsk::Config::RxBw::HZ_83300, + .afc_bw = SX1278Fsk::Config::RxBw::HZ_125000, .ocp = 120, .power = 17, - .shaping = Boardcore::SX1278Fsk::Shaping::GAUSSIAN_BT_1_0, - .dc_free = Boardcore::SX1278Fsk::DcFree::WHITENING}; + .shaping = SX1278Fsk::Config::Shaping::GAUSSIAN_BT_1_0, + .dc_free = SX1278Fsk::Config::DcFree::WHITENING}; SX1278Fsk::Error err; SPIBus bus(SX1278_SPI);