diff --git a/CMakeLists.txt b/CMakeLists.txt index ea116b5211996b039464de1848fedba46988f799..ed560e57e4b1e490afe4781e79a23b95721d933f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -195,6 +195,46 @@ sbs_target(test-stepper stm32f429zi_stm32f4discovery) add_executable(test-fsm src/tests/events/fsm/test-fsm.cpp) sbs_target(test-fsm stm32f429zi_stm32f4discovery) +#-----------------------------------------------------------------------------# +# Tests - Radio # +#-----------------------------------------------------------------------------# + +add_executable(test-sx1278-bench + src/tests/drivers/sx1278/test-sx1278-bench.cpp + src/tests/drivers/sx1278/test-sx1278-core.cpp +) +sbs_target(test-sx1278-bench stm32f407vg_stm32f4discovery) + +add_executable(test-sx1278-bidir + src/tests/drivers/sx1278/test-sx1278-bidir.cpp + src/tests/drivers/sx1278/test-sx1278-core.cpp +) +sbs_target(test-sx1278-bidir stm32f407vg_stm32f4discovery) + +add_executable(test-sx1278-tx + src/tests/drivers/sx1278/test-sx1278-tx.cpp + src/tests/drivers/sx1278/test-sx1278-core.cpp +) +sbs_target(test-sx1278-tx stm32f407vg_stm32f4discovery) + +add_executable(test-sx1278-rx + src/tests/drivers/sx1278/test-sx1278-rx.cpp + src/tests/drivers/sx1278/test-sx1278-core.cpp +) +sbs_target(test-sx1278-rx stm32f407vg_stm32f4discovery) + +add_executable(test-sx1278-mavlink + src/tests/drivers/sx1278/test-sx1278-mavlink.cpp + src/tests/drivers/sx1278/test-sx1278-core.cpp +) +sbs_target(test-sx1278-mavlink stm32f407vg_stm32f4discovery) + +add_executable(test-sx1278-serial + src/tests/drivers/sx1278/test-sx1278-serial.cpp + src/tests/drivers/sx1278/test-sx1278-core.cpp +) +sbs_target(test-sx1278-serial stm32f407vg_stm32f4discovery) + #-----------------------------------------------------------------------------# # Tests - Sensors # #-----------------------------------------------------------------------------# diff --git a/cmake/boardcore.cmake b/cmake/boardcore.cmake index 979aa24005d368b63bb645051dc14523a4164089..1a09f8814b39f584ce85adc67fe80b12eb158874 100644 --- a/cmake/boardcore.cmake +++ b/cmake/boardcore.cmake @@ -43,6 +43,7 @@ foreach(OPT_BOARD ${BOARDS}) ${SBS_BASE}/src/shared/drivers/runcam/Runcam.cpp ${SBS_BASE}/src/shared/drivers/servo/Servo.cpp ${SBS_BASE}/src/shared/drivers/spi/SPITransaction.cpp + ${SBS_BASE}/src/shared/drivers/SX1278/SX1278.cpp # Events ${SBS_BASE}/src/shared/events/EventBroker.cpp diff --git a/src/shared/drivers/SX1278/SX1278.cpp b/src/shared/drivers/SX1278/SX1278.cpp new file mode 100644 index 0000000000000000000000000000000000000000..52a91f3ba06520aa4b18974468319a22256b6774 --- /dev/null +++ b/src/shared/drivers/SX1278/SX1278.cpp @@ -0,0 +1,476 @@ +/* Copyright (c) 2021 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 "SX1278.h" + +#include <kernel/scheduler/scheduler.h> + +#include <cmath> + +namespace Boardcore +{ + +using namespace SX1278Defs; + +// 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; + +SX1278BusManager::SX1278BusManager(SPIBusInterface &bus, miosix::GpioPin cs) + : slave(bus, cs, spiConfig()), mode(SX1278BusManager::Mode::MODE_SLEEP) +{ +} + +void SX1278BusManager::lock(SX1278BusManager::Mode mode) +{ + mutex.lock(); + + enterMode(mode); + irq_wait_thread = nullptr; +} + +void SX1278BusManager::unlock() +{ + if (rx_wait_thread != nullptr) + { + // Restore rx state + irq_wait_thread = rx_wait_thread; + enterMode(SX1278BusManager::Mode::MODE_RX); + } + + mutex.unlock(); +} + +SPISlave &SX1278BusManager::getBus() { return slave; } + +void SX1278BusManager::handleDioIRQ() +{ + if (irq_wait_thread) + { + irq_wait_thread->IRQwakeup(); + if (irq_wait_thread->IRQgetPriority() > + miosix::Thread::IRQgetCurrentThread()->IRQgetPriority()) + { + miosix::Scheduler::IRQfindNextThread(); + } + + // Check if we woke the rx thread + if (irq_wait_thread == rx_wait_thread) + rx_wait_thread = nullptr; + + irq_wait_thread = nullptr; + } +} + +void SX1278BusManager::waitForIrq(uint16_t mask) +{ + // Tight loop on IRQ register + while (!(getIrqFlags() & mask)) + miosix::delayUs(10); +} + +void SX1278BusManager::waitForRxIrq() +{ + // NOTE: waitForRxIrq is only available for RX + + // Check before entering irq mode + if (getIrqFlags() & RegIrqFlags::PAYLOAD_READY) + return; + + miosix::FastInterruptDisableLock dLock; + irq_wait_thread = rx_wait_thread = miosix::Thread::getCurrentThread(); + // Release lock to allow for writers + mutex.unlock(); + + // Avoid spurious wakeups + while (rx_wait_thread != 0) + { + rx_wait_thread->IRQwait(); + { + miosix::FastInterruptEnableLock eLock(dLock); + miosix::Thread::yield(); + } + } + + // Regain ownership of the lock + mutex.lock(); +} + +void SX1278BusManager::enterMode(Mode mode) +{ + // Check if necessary + if (mode == this->mode) + return; + + setMode(mode); + + // BUG: Removing the next line makes it, better?!? + // waitForIrq(RegIrqFlags::MODE_READY); + + this->mode = mode; +} + +uint16_t SX1278BusManager::getIrqFlags() +{ + SPITransaction spi(getBus(), SPITransaction::WriteBit::INVERTED); + + uint8_t flags[2] = {0, 0}; + spi.readRegisters(REG_IRQ_FLAGS_1, flags, 2); + + return (flags[0] | flags[1] << 8); +} + +void SX1278BusManager::setMode(Mode mode) +{ + SPITransaction spi(getBus(), SPITransaction::WriteBit::INVERTED); + spi.writeRegister(REG_OP_MODE, REG_OP_MODE_DEFAULT | mode); +} + +SX1278::SX1278(SPIBusInterface &bus, miosix::GpioPin cs) : bus_mgr(bus, cs) {} + +SX1278::Error SX1278::init(Config config) +{ + // Lock the bus + bus_mgr.lock(Mode::MODE_STDBY); + bus_mgr.waitForIrq(RegIrqFlags::MODE_READY); + + if (getVersion() != 0x12) + { + return Error::BAD_VERSION; + } + + 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); + setPreableLen(2); + setPa(config.power, true); + + // Setup generic parameters + { + SPITransaction spi(bus_mgr.getBus(), + SPITransaction::WriteBit::INVERTED); + + spi.writeRegister(REG_PA_RAMP, + RegPaRamp::MODULATION_SHAPING_NONE | 0x09); + spi.writeRegister(REG_RX_CONFIG, + RegRxConfig::AFC_AUTO_ON | RegRxConfig::AGC_AUTO_ON | + RegRxConfig::RX_TRIGGER_PREAMBLE_DETECT | + RegRxConfig::RX_TRIGGER_RSSI_INTERRUPT); + spi.writeRegister(REG_RSSI_THRESH, 0xff); + spi.writeRegister( + REG_PREAMBLE_DETECT, + RegPreambleDetector::PREAMBLE_DETECTOR_ON | + RegPreambleDetector::PREAMBLE_DETECTOR_SIZE_2_BYTES | 0x0a); + 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 | + RegPacketConfig1::DC_FREE_NONE | + 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_FIFO_THRESH, + RegFifoThresh::TX_START_CONDITION_FIFO_NOT_EMPTY | 0x0f); + spi.writeRegister(REG_NODE_ADRS, 0x00); + spi.writeRegister(REG_BROADCAST_ADRS, 0x00); + + // Enable PayloadReady, PacketSent on DIO0 + spi.writeRegister(REG_DIO_MAPPING_1, 0x00); + } + + bus_mgr.unlock(); + return Error::NONE; +} + +ssize_t SX1278::receive(uint8_t *pkt, size_t max_len) +{ + bus_mgr.lock(Mode::MODE_RX); + + uint8_t len = 0; + do + { + // Special wait for payload ready + bus_mgr.waitForRxIrq(); + + { + SPITransaction spi(bus_mgr.getBus(), + SPITransaction::WriteBit::INVERTED); + len = spi.readRegister(REG_FIFO); + if (len > max_len) + return -1; + + spi.readRegisters(REG_FIFO, pkt, len); + } + + // For some reason this sometimes happen? + } while (len == 0); + + bus_mgr.unlock(); + return len; +} + +bool SX1278::send(uint8_t *pkt, size_t len) +{ + // Packets longer than 255 are not supported + if (len > 255) + return false; + + bus_mgr.lock(SX1278BusManager::Mode::MODE_TX); + + // Wait for TX ready + bus_mgr.waitForIrq(RegIrqFlags::TX_READY); + + { + SPITransaction spi(bus_mgr.getBus(), + SPITransaction::WriteBit::INVERTED); + + spi.writeRegister(REG_FIFO, static_cast<uint8_t>(len)); + spi.writeRegisters(REG_FIFO, pkt, len); + } + + // Wait for packet sent + bus_mgr.waitForIrq(RegIrqFlags::PACKET_SENT); + bus_mgr.unlock(); + return true; +} + +void SX1278::handleDioIRQ() { bus_mgr.handleDioIRQ(); } + +uint8_t SX1278::getVersion() +{ + SPITransaction spi(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + + return spi.readRegister(REG_VERSION); +} + +void SX1278::setBitrate(int bitrate) +{ + uint16_t val = SX1278Defs::FXOSC / bitrate; + + // Update values + SPITransaction spi(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + spi.writeRegister(REG_BITRATE_MSB, val >> 8); + spi.writeRegister(REG_BITRATE_LSB, val); +} + +void SX1278::setFreqDev(int freq_dev) +{ + uint16_t val = freq_dev / FSTEP; + + // Update values + SPITransaction spi(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + spi.writeRegister(REG_FDEV_MSB, (val >> 8) & 0x3f); + spi.writeRegister(REG_FDEV_LSB, val); +} + +void SX1278::setFreqRF(int freq_rf) +{ + uint32_t val = freq_rf / FSTEP; + + // Update values + SPITransaction spi(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + spi.writeRegister(REG_FRF_MSB, val >> 16); + spi.writeRegister(REG_FRF_MID, val >> 8); + spi.writeRegister(REG_FRF_LSB, val); +} + +void SX1278::setOcp(int ocp) +{ + SPITransaction spi(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + 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 SX1278::setSyncWord(uint8_t value[], int size) +{ + SPITransaction spi(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + 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 SX1278::setRxBw(RxBw rx_bw) +{ + SPITransaction spi(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + spi.writeRegister(REG_RX_BW, static_cast<uint8_t>(rx_bw)); +} + +void SX1278::setAfcBw(RxBw afc_bw) +{ + SPITransaction spi(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + spi.writeRegister(REG_AFC_BW, static_cast<uint8_t>(afc_bw)); +} + +void SX1278::setPreableLen(int len) +{ + SPITransaction spi(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + spi.writeRegister(REG_PREAMBLE_MSB, len >> 8); + spi.writeRegister(REG_PREAMBLE_LSB, len); +} + +void SX1278::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(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + + 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 SX1278::debugDumpRegisters() +{ + 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(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED); + + 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/drivers/SX1278/SX1278.h b/src/shared/drivers/SX1278/SX1278.h new file mode 100644 index 0000000000000000000000000000000000000000..6fb4c355d36f81331e7299e6a291e58c737e4156 --- /dev/null +++ b/src/shared/drivers/SX1278/SX1278.h @@ -0,0 +1,247 @@ +/* Copyright (c) 2021 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 <diagnostic/PrintLogger.h> +#include <drivers/spi/SPIDriver.h> +#include <kernel/kernel.h> +#include <radio/Transceiver.h> + +#include <cstdint> + +#include "SX1278Defs.h" + +/* +# Description +## Concurrent access +The device is stateful, in order to send/receive data you need to set in a +particular state. This is handled by SX1278BusManager::setMode. This causes a +lot of issues with multithreaded code, and receiving/transmitting concurrently. + +So the driver wraps the bus in a BusManager for this reason, in order to perform +anything you need to lock the bus. The driver then locks the internal mutex and +sets the device in the correct mode for that operation. + +But this causes problems when receiving, as receive can block indefinetly, and +would prevent any thread from actually sending stuff. The solution is to release +the lock only when waiting for a packet. This allows other threads to lock it +and change mode, and unlocking the bus resets its state back to RX so it can +continue to listen for incoming packets. + +The BusManager also multiplexes who is currently waiting for an interrupt. This +is needed because due to the limited interrupts pins, the device signals +multiples of them on one pin. And for some random reasons, the designers decided +to put "packet received" and "packed sent" on same pin (DIO0)... + +Again, the solution is to track who is actually using the bus, so when sending a +packet that triggers the "packet sent" interrupt, the manager knows to dispatch +it to the currect thread, and not wake up the RX thread. +*/ + +namespace Boardcore +{ + +/** + * @brief SX1278 bus access manager. + */ +class SX1278BusManager +{ +public: + using Mode = SX1278Defs::RegOpMode::Mode; + + SX1278BusManager(SPIBusInterface &bus, miosix::GpioPin cs); + + /** + * @brief Lock bus for exclusive access. + * + * @param mode Device mode requested + */ + void lock(Mode mode); + + /** + * @brief Release buf for exclusive access + */ + void unlock(); + + /** + * @brief Get underlying bus. + */ + SPISlave &getBus(); + + /** + * @brief Handle DIO0 irq. + */ + void handleDioIRQ(); + + /** + * @brief Wait for generic irq (DOES NOT RELEASE LOCK!). + */ + void waitForIrq(uint16_t mask); + + /** + * @brief Wait for RX irq (releases lock safely). + */ + void waitForRxIrq(); + +private: + void enterMode(Mode mode); + + uint16_t getIrqFlags(); + void setMode(Mode mode); + + miosix::Thread *irq_wait_thread = nullptr; + miosix::Thread *rx_wait_thread = nullptr; + miosix::FastMutex mutex; + + SPISlave slave; + Mode mode; +}; + +/** + * @brief Various SX1278 register/enums definitions. + */ +class SX1278 : public Transceiver +{ +public: + /** + * @brief Channel filter bandwidth. + */ + enum class RxBw + { + HZ_2600 = (0b10 << 3) | 7, + HZ_3100 = (0b01 << 3) | 7, + HZ_3900 = (0b00 << 3) | 7, + HZ_5200 = (0b10 << 3) | 6, + HZ_6300 = (0b01 << 3) | 6, + HZ_7800 = (0b00 << 3) | 6, + HZ_10400 = (0b10 << 3) | 5, + HZ_12500 = (0b01 << 3) | 5, + HZ_15600 = (0b00 << 3) | 5, + HZ_20800 = (0b10 << 3) | 4, + HZ_25000 = (0b01 << 3) | 4, + HZ_31300 = (0b00 << 3) | 4, + HZ_41700 = (0b10 << 3) | 3, + HZ_50000 = (0b01 << 3) | 3, + HZ_62500 = (0b00 << 3) | 3, + HZ_83300 = (0b10 << 3) | 2, + HZ_100000 = (0b01 << 3) | 2, + HZ_125000 = (0b00 << 3) | 2, + HZ_166700 = (0b10 << 3) | 1, + HZ_200000 = (0b01 << 3) | 1, + HZ_250000 = (0b00 << 3) | 1, + }; + + /** + * @brief Requested SX1278 configuration. + */ + struct Config + { + int freq_rf = 434000000; //< RF Frequency in Hz. + int freq_dev = 50000; //< Frequency deviation in Hz. + int bitrate = 48000; //< Bitrate in b/s. + RxBw rx_bw = RxBw::HZ_125000; //< Rx filter bandwidth. + 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 + // full power). + }; + + /** + * @brief Error enum. + */ + enum class Error + { + NONE, //< No error encountered. + BAD_VALUE, //< A requested value was outside the valid range. + BAD_VERSION, //< Chip didn't report the correct version. + }; + + /** + * @brief Construct a new SX1278 + * + * @param bus SPI bus used. + * @param cs Chip select pin. + */ + SX1278(SPIBusInterface &bus, miosix::GpioPin cs); + + /** + * @brief Setup the device. + */ + Error init(Config config); + + /** + * @brief Wait until a new packet is received. + * + * @param pkt Buffer to store the received packet into. + * @param pkt_len Maximum length of the received data. + * @return Size of the data received or -1 if failure + */ + ssize_t receive(uint8_t *pkt, size_t max_len); + + /** + * @brief Send a packet. + * The function must block until the packet is sent (successfully or not) + * + * @param pkt Pointer to the packet (needs to be at least pkt_len + * bytes). + * @param pkt_len Lenght of the packet to be sent. + * @return True if the message was sent correctly. + */ + bool send(uint8_t *pkt, size_t len); + + /** + * @brief Return device version. + */ + uint8_t getVersion(); + + /** + * @brief Handle an incoming interrupt. + */ + void handleDioIRQ(); + + /** + * @brief Dump all registers via TRACE. + */ + void debugDumpRegisters(); + +public: + using Mode = SX1278BusManager::Mode; + + 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 setPreableLen(int len); + void setPa(int power, bool pa_boost); + + void waitForIrq(uint16_t mask); + + SX1278BusManager bus_mgr; + PrintLogger logger = Logging::getLogger("sx1278"); +}; + +} // namespace Boardcore diff --git a/src/shared/drivers/SX1278/SX1278Defs.h b/src/shared/drivers/SX1278/SX1278Defs.h new file mode 100644 index 0000000000000000000000000000000000000000..cd50d09a8c3294659f1c1186f2ad1fd0512937c6 --- /dev/null +++ b/src/shared/drivers/SX1278/SX1278Defs.h @@ -0,0 +1,356 @@ +/* Copyright (c) 2021 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 <drivers/spi/SPIDriver.h> + +namespace Boardcore +{ + +/** + * @brief Various SX1278 register/enums definitions. + */ +namespace SX1278Defs +{ + +/** + * @brief Main oscillator frequency (Hz) + */ +constexpr int FXOSC = 32000000; + +/** + * @brief Frequency step (Hz) used in some calculations. + */ +constexpr int FSTEP = 61; + +constexpr int TS_OSC = 250; +constexpr int TS_FS = 60; + +/** + * @brief Get required spi config + */ +inline SPIBusConfig spiConfig() +{ + SPIBusConfig config = {}; + + // FIXME(davide.mor): This depends on the device + config.clockDivider = SPI::ClockDivider::DIV_64; + config.mode = SPI::Mode::MODE_1; + config.bitOrder = SPI::BitOrder::MSB_FIRST; + // config.cs_setup_time_us = 30; + // config.cs_hold_time_us = 100; + + return config; +} + +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, + MODE_STDBY = 0b001, + MODE_FSTX = 0b010, + MODE_TX = 0b011, + MODE_FSRX = 0b100, + MODE_RX = 0b101, +}; +} // namespace RegOpMode + +namespace RegPaConfig +{ +constexpr uint8_t PA_SELECT_BOOST = 1 << 7; +} + +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, +}; +} + +namespace RegOcp +{ +constexpr uint8_t OCP_ON = 1 << 5; +} + +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; +} // namespace RegRxConfig + +namespace RegPreambleDetector +{ +constexpr uint8_t PREAMBLE_DETECTOR_ON = 1 << 7; + +enum PreambleDetectorSize +{ + PREAMBLE_DETECTOR_SIZE_1_BYTE = 0b00 << 5, + PREAMBLE_DETECTOR_SIZE_2_BYTES = 0b01 << 5, + PREAMBLE_DETECTOR_SIZE_3_BYTES = 0b10 << 5, +}; +} // 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, +}; + +enum PreamblePolarity +{ + PREAMBLE_POLARITY_AA = 0 << 5, + PREAMBLE_POLARITY_55 = 1 << 5, +}; + +constexpr uint8_t SYNC_ON = 1 << 4; +} // namespace RegSyncConfig + +namespace RegPacketConfig1 +{ +enum PacketFormat +{ + PACKET_FORMAT_FIXED_LENGTH = 0 << 7, + PACKET_FORMAT_VARIABLE_LENGTH = 1 << 7, +}; + +enum DcFree +{ + DC_FREE_NONE = 0b00 << 5, + DC_FREE_MANCHESTER = 0b01 << 5, + DC_FREE_WHITENING = 0b10 << 5, +}; + +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, +}; + +enum CrcWhiteningType +{ + CRC_WHITENING_TYPE_CCITT_CRC = 0, + CRC_WHITENING_TYPE_IBM_CRC = 1, +}; +} // namespace RegPacketConfig1 + +namespace RegPacketConfig2 +{ +enum DataMode +{ + DATA_MODE_CONTINUOS = 0 << 6, + DATA_MODE_PACKET = 1 << 6 +}; + +constexpr uint8_t IO_HOME_ON = 1 << 5; +constexpr uint8_t BEACON_ON = 1 << 4; +} // namespace RegPacketConfig2 + +namespace RegFifoThresh +{ +enum TxStartCondition +{ + TX_START_CONDITION_FIFO_LEVEL = 0 << 7, + TX_START_CONDITION_FIFO_NOT_EMPTY = 1 << 7, +}; +} + +namespace RegIrqFlags +{ +constexpr uint16_t MODE_READY = 1 << 7; +constexpr uint16_t RX_READY = 1 << 6; +constexpr uint16_t TX_READY = 1 << 5; +constexpr uint16_t PILL_LOCK = 1 << 4; +constexpr uint16_t RSSI = 1 << 3; +constexpr uint16_t TIMEOUT = 1 << 2; +constexpr uint16_t PREAMBLE_DETECT = 1 << 1; +constexpr uint16_t SYNC_ADDRESS_MATCH = 1 << 0; +constexpr uint16_t FIFO_FULL = 1 << 15; +constexpr uint16_t FIFO_EMPTY = 1 << 14; +constexpr uint16_t FIFO_LEVEL = 1 << 13; +constexpr uint16_t FIFO_OVERRUN = 1 << 12; +constexpr uint16_t PACKET_SENT = 1 << 11; +constexpr uint16_t PAYLOAD_READY = 1 << 10; +constexpr uint16_t CRC_OK = 1 << 9; +constexpr uint16_t LOW_BAT = 1 << 8; + +} // namespace RegIrqFlags + +namespace RegPaDac +{ +enum PaDac +{ + PA_DAC_DEFAULT_VALUE = 0x04, + PA_DAC_PA_BOOST = 0x07 +}; +} + +enum Registers +{ + REG_FIFO = 0x00, + + // Registers for common settings + REG_OP_MODE = 0x01, + REG_BITRATE_MSB = 0x02, + REG_BITRATE_LSB = 0x03, + REG_FDEV_MSB = 0x04, + REG_FDEV_LSB = 0x05, + REG_FRF_MSB = 0x06, + REG_FRF_MID = 0x07, + REG_FRF_LSB = 0x08, + + // Registers for the transmitter + REG_PA_CONFIG = 0x09, + REG_PA_RAMP = 0x0a, + REG_OCP = 0x0b, + + // Registers for the receiver + REG_LNA = 0x0c, + REG_RX_CONFIG = 0x0d, + REG_RSSI_CONFIG = 0x0e, + REG_RSSI_COLLISION = 0x0f, + REG_RSSI_THRESH = 0x10, + REG_RSSI_VALUE = 0x11, + REG_RX_BW = 0x12, + REG_AFC_BW = 0x13, + REG_OOK_PEAK = 0x14, + REG_OOK_FIX = 0x15, + REG_OOK_AVG = 0x16, + // Reserved 17 to 19 + REG_AFC_FEI = 0x1a, + REG_AFC_MSB = 0x1b, + REG_AFC_LSB = 0x1c, + REG_FEI_MSB = 0x1d, + REG_FEI_LSB = 0x1e, + REG_PREAMBLE_DETECT = 0x1f, + REG_RX_TIMEOUT_1 = 0x20, + REG_RX_TIMEOUT_2 = 0x21, + REG_RX_TIMEOUT_3 = 0x22, + REG_RX_DELAY = 0x23, + + // RC Oscillator registers + REG_OSC = 0x24, + + // Packet handling registers + REG_PREAMBLE_MSB = 0x25, + REG_PREAMBLE_LSB = 0x26, + REG_SYNC_CONFIG = 0x27, + REG_SYNC_VALUE_1 = 0x28, + REG_SYNC_VALUE_2 = 0x29, + REG_SYNC_VALUE_3 = 0x2a, + REG_SYNC_VALUE_4 = 0x2b, + REG_SYNC_VALUE_5 = 0x2c, + REG_SYNC_VALUE_6 = 0x2d, + REG_SYNC_VALUE_7 = 0x2e, + REG_SYNC_VALUE_8 = 0x2f, + REG_PACKET_CONFIG_1 = 0x30, + REG_PACKET_CONFIG_2 = 0x31, + REG_PACKET_PAYLOAD_LENGTH = 0x32, + REG_NODE_ADRS = 0x33, + REG_BROADCAST_ADRS = 0x34, + REG_FIFO_THRESH = 0x35, + + // Sequencer registers + REG_SEQ_CONFIG_1 = 0x36, + REG_SEQ_CONFIG_2 = 0x37, + REG_TIMER_RESOL = 0x38, + REG_TIMER_1_COEF = 0x39, + REG_TIMER_2_COEF = 0x3a, + + // Service registers + REG_IMAGE_CAL = 0x3b, + REG_TEMP = 0x3c, + REG_LOW_BAT = 0x3d, + + // Status registers + REG_IRQ_FLAGS_1 = 0x3e, + REG_IRQ_FLAGS_2 = 0x3f, + + // IO Control registers + REG_DIO_MAPPING_1 = 0x40, + REG_DIO_MAPPING_2 = 0x41, + + // Version register + REG_VERSION = 0x42, + + // Additional registers + REG_PILL_HOP = 0x44, + REG_TCXO = 0x4b, + REG_PA_DAC = 0x4d, + REG_FORMER_TEMP = 0x5b, + REG_BITRATE_FRAC = 0x5d, + REG_AGC_REF = 0x61, + REG_AGC_THRESH_1 = 0x62, + REG_AGC_THRESH_2 = 0x63, + REG_AGC_THRESH_3 = 0x64, + + // Low frequency additional registers + REG_AGC_REF_LF = 0x61, + REG_AGC_THRESH_1_LF = 0x62, + REG_AGC_THRESH_2_LF = 0x63, + REG_AGC_THRESH_3_LF = 0x61, + REG_AGC_PILL_LF = 0x70, + + // High frequency additional registers + REG_AGC_REF_HF = 0x61, + REG_AGC_THRESH_1_HF = 0x62, + REG_AGC_THRESH_2_HF = 0x63, + REG_AGC_THRESH_3_HF = 0x61, + REG_AGC_PILL_HF = 0x70, +}; + +} // namespace SX1278Defs + +} // namespace Boardcore diff --git a/src/tests/drivers/sx1278/test-sx1278-bench.cpp b/src/tests/drivers/sx1278/test-sx1278-bench.cpp new file mode 100644 index 0000000000000000000000000000000000000000..5ddb67f00a8800f77f5597fa3c9538fb8496a6e5 --- /dev/null +++ b/src/tests/drivers/sx1278/test-sx1278-bench.cpp @@ -0,0 +1,315 @@ +/* Copyright (c) 2021 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 <drivers/SX1278/SX1278.h> +#include <drivers/interrupt/external_interrupts.h> + +#include <thread> + +#include "test-sx1278-core.h" + +using namespace Boardcore; +using namespace miosix; + +/** + * 0 -> RX + * 1 -> TX + * + * Connection diagram: + * sx1278[0]:nss -> stm32:pa1 + * sx1278[0]:dio0 -> stm32:pc15 + * sx1278[0]:mosi -> stm32:pc12 (SPI3_MOSI) + * sx1278[0]:miso -> stm32:pc11 (SPI3_MISO) + * sx1278[0]:sck -> stm32:pc10 (SPI3_SCK) + + * sx1278[1]:nss -> stm32:pa2 + * sx1278[1]:dio0 -> stm32:pc0 + * sx1278[1]:mosi -> stm32:pb15 (SPI2_MOSI) + * sx1278[1]:miso -> stm32:pb14 (SPI2_MISO) + * sx1278[1]:sck -> stm32:pb13 (SPI2_SCK) + */ + +SPIBus bus0(SPI3); +SPIBus bus1(SPI2); + +GpioPin sck0(GPIOC_BASE, 10); +GpioPin miso0(GPIOC_BASE, 11); +GpioPin mosi0(GPIOC_BASE, 12); +GpioPin cs0(GPIOA_BASE, 1); +GpioPin dio0(GPIOC_BASE, 15); + +GpioPin sck1(GPIOB_BASE, 13); +GpioPin miso1(GPIOB_BASE, 14); +GpioPin mosi1(GPIOB_BASE, 15); +GpioPin cs1(GPIOA_BASE, 2); +GpioPin dio1(GPIOC_BASE, 0); + +struct Stats; + +const char *stringFromErr(SX1278::Error err); +const char *stringFromRxBw(SX1278::RxBw rx_bw); + +void printStats(Stats stats); + +/// Status informations. +struct Stats +{ + int last_recv_packet = 0; //< Last received packet ID. + int corrupted_packets = 0; //< Packets that got mangled during tx. + int send_count = 0; //< Actual number of packets sent. + int recv_count = 0; //< Actual number of packets received. + int recv_errors = 0; //< Number of failed recvs. + + float packet_loss() const + { + if (last_recv_packet != 0) + { + return 1.0f - ((float)recv_count / (float)last_recv_packet); + } + else + { + return 0.0f; + } + } + +} stats; + +/// Interval between transmissions. +const int TX_INTERVAL = 1; + +SX1278 *sx1278[2] = {nullptr, nullptr}; + +struct Msg +{ + int idx; + int dummy_1; + int dummy_2; + int dummy_3; + + const static int DUMMY_1 = 0xdeadbeef; + const static int DUMMY_2 = 0xbeefdead; + const static int DUMMY_3 = 0x1234abcd; +}; + +void recvLoop(int idx) +{ + while (1) + { + Msg msg; + msg.idx = 0; + msg.dummy_1 = 0; + msg.dummy_2 = 0; + msg.dummy_3 = 0; + + int len = sx1278[idx]->receive((uint8_t *)&msg, sizeof(msg)); + if (len != sizeof(msg)) + { + stats.recv_errors++; + } + else if (msg.dummy_1 != Msg::DUMMY_1 || msg.dummy_2 != Msg::DUMMY_2 || + msg.dummy_3 != Msg::DUMMY_3) + { + stats.recv_errors++; + stats.corrupted_packets++; + } + else + { + stats.last_recv_packet = msg.idx; + stats.recv_count++; + } + } +} + +void sendLoop(int idx) +{ + while (1) + { + miosix::Thread::sleep(TX_INTERVAL); + + int next_idx = stats.send_count + 1; + + Msg msg; + msg.idx = next_idx; + msg.dummy_1 = Msg::DUMMY_1; + msg.dummy_2 = Msg::DUMMY_2; + msg.dummy_3 = Msg::DUMMY_3; + + sx1278[idx]->send((uint8_t *)&msg, sizeof(msg)); + stats.send_count = next_idx; + } +} + +/// Get current time +long long now() { return miosix::getTick() * 1000 / miosix::TICK_FREQ; } + +void __attribute__((used)) EXTI15_IRQHandlerImpl() +{ + if (sx1278[0]) + sx1278[0]->handleDioIRQ(); +} + +void __attribute__((used)) EXTI0_IRQHandlerImpl() +{ + if (sx1278[1]) + sx1278[1]->handleDioIRQ(); +} + +/// Initialize stm32f407g board (sx1278[0] only) +void initBoard0() +{ + { + miosix::FastInterruptDisableLock dLock; + + // Enable SPI3 + RCC->APB1ENR |= RCC_APB1ENR_SPI3EN; + RCC_SYNC(); + + // Setup SPI pins + sck0.mode(miosix::Mode::ALTERNATE); + sck0.alternateFunction(6); + miso0.mode(miosix::Mode::ALTERNATE); + miso0.alternateFunction(6); + mosi0.mode(miosix::Mode::ALTERNATE); + mosi0.alternateFunction(6); + + cs0.mode(miosix::Mode::OUTPUT); + dio0.mode(miosix::Mode::INPUT); + } + + cs0.high(); + enableExternalInterrupt(dio0.getPort(), dio0.getNumber(), + InterruptTrigger::RISING_EDGE); +} + +/// Initialize stm32f407g board (sx1278[1] only) +void initBoard1() +{ + { + miosix::FastInterruptDisableLock dLock; + + // Enable SPI2 + RCC->APB1ENR |= RCC_APB1ENR_SPI2EN; + RCC_SYNC(); + + sck1.mode(miosix::Mode::ALTERNATE); + sck1.alternateFunction(5); + miso1.mode(miosix::Mode::ALTERNATE); + miso1.alternateFunction(5); + mosi1.mode(miosix::Mode::ALTERNATE); + mosi1.alternateFunction(5); + + cs1.mode(miosix::Mode::OUTPUT); + dio1.mode(miosix::Mode::INPUT); + } + + cs1.high(); + enableExternalInterrupt(dio1.getPort(), dio1.getNumber(), + InterruptTrigger::RISING_EDGE); +} + +int main() +{ +#ifndef DISABLE_RX + initBoard0(); +#endif +#ifndef DISABLE_TX + initBoard1(); +#endif + + // Run default configuration + SX1278::Config config; + SX1278::Error err; + + // Configure them +#ifndef DISABLE_RX + sx1278[0] = new SX1278(bus0, cs0); + + printf("\n[sx1278] Configuring sx1278[0]...\n"); + printConfig(config); + if ((err = sx1278[0]->init(config)) != SX1278::Error::NONE) + { + printf("[sx1278] sx1278[0]->init error: %s\n", stringFromErr(err)); + return -1; + } +#endif + +#ifndef DISABLE_TX + sx1278[1] = new SX1278(bus1, cs1); + + printf("\n[sx1278] Configuring sx1278[1]...\n"); + printConfig(config); + if ((err = sx1278[1]->init(config)) != SX1278::Error::NONE) + { + printf("[sx1278] sx1278[1]->init error: %s\n", stringFromErr(err)); + return -1; + } +#endif + + // Run background threads +#ifndef DISABLE_RX + std::thread recv([]() { recvLoop(0); }); +#endif +#ifndef DISABLE_TX + std::thread send([]() { sendLoop(1); }); +#endif + + // Finish! + long long start = now(); + + printf("\n[sx1278] Initialization complete!\n"); + + miosix::Thread::sleep(4000); + + while (1) + { + long long elapsed = now() - start; + + // Calculate bitrates + float tx_bitrate = (float)(stats.send_count * sizeof(Msg) * 8) / + ((float)elapsed / 1000.0f); + + float rx_bitrate = (float)(stats.recv_count * sizeof(Msg) * 8) / + ((float)elapsed / 1000.0f); + + printf("\n[sx1278] Stats:\n"); + printStats(stats); + printf("tx_bitrate: %.2f kb/s\n", tx_bitrate / 1000.0f); + printf("rx_bitrate: %.2f kb/s\n", rx_bitrate / 1000.0f); + + miosix::Thread::sleep(2000); + } + + return 0; +} + +void printStats(Stats stats) +{ + // Prints are REALLY slow, so take a COPY of stats, so we can print an + // instant in time. + + printf("stats.last_recv_packet = %d\n", stats.last_recv_packet); + printf("stats.corrupted_packets = %d\n", stats.corrupted_packets); + printf("stats.send_count = %d\n", stats.send_count); + printf("stats.recv_count = %d\n", stats.recv_count); + printf("stats.recv_errors = %d\n", stats.recv_errors); + printf("stats.packet_loss = %.2f %%\n", stats.packet_loss() * 100.0f); +} diff --git a/src/tests/drivers/sx1278/test-sx1278-bidir.cpp b/src/tests/drivers/sx1278/test-sx1278-bidir.cpp new file mode 100644 index 0000000000000000000000000000000000000000..6ecf7b42664660dd6331bf8c707f130135216e3b --- /dev/null +++ b/src/tests/drivers/sx1278/test-sx1278-bidir.cpp @@ -0,0 +1,201 @@ +/* Copyright (c) 2021 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 <drivers/SX1278/SX1278.h> +#include <drivers/interrupt/external_interrupts.h> + +#include <cstring> +#include <thread> + +#include "test-sx1278-core.h" + +using namespace Boardcore; +using namespace miosix; + +/** + * Connection diagram: + * sx1278[0]:nss -> stm32:pa1 + * sx1278[0]:dio0 -> stm32:pc15 + * sx1278[0]:mosi -> stm32:pc12 (SPI3_MOSI) + * sx1278[0]:miso -> stm32:pc11 (SPI3_MISO) + * sx1278[0]:sck -> stm32:pc10 (SPI3_SCK) + + * sx1278[1]:nss -> stm32:pa2 + * sx1278[1]:dio0 -> stm32:pc0 + * sx1278[1]:mosi -> stm32:pb15 (SPI2_MOSI) + * sx1278[1]:miso -> stm32:pb14 (SPI2_MISO) + * sx1278[1]:sck -> stm32:pb13 (SPI2_SCK) + */ + +SPIBus bus0(SPI3); +SPIBus bus1(SPI2); + +GpioPin sck0(GPIOC_BASE, 10); +GpioPin miso0(GPIOC_BASE, 11); +GpioPin mosi0(GPIOC_BASE, 12); +GpioPin cs0(GPIOA_BASE, 1); +GpioPin dio0(GPIOC_BASE, 15); + +GpioPin sck1(GPIOB_BASE, 13); +GpioPin miso1(GPIOB_BASE, 14); +GpioPin mosi1(GPIOB_BASE, 15); +GpioPin cs1(GPIOA_BASE, 2); +GpioPin dio1(GPIOC_BASE, 0); + +SX1278 *sx1278[2] = {nullptr, nullptr}; + +void __attribute__((used)) EXTI15_IRQHandlerImpl() +{ + if (sx1278[0]) + sx1278[0]->handleDioIRQ(); +} + +void __attribute__((used)) EXTI0_IRQHandlerImpl() +{ + if (sx1278[1]) + sx1278[1]->handleDioIRQ(); +} + +/// Initialize stm32f407g board (sx1278[0] only) +void initBoard0() +{ + { + miosix::FastInterruptDisableLock dLock; + + // Enable SPI3 + RCC->APB1ENR |= RCC_APB1ENR_SPI3EN; + RCC_SYNC(); + + // Setup SPI pins + sck0.mode(miosix::Mode::ALTERNATE); + sck0.alternateFunction(6); + miso0.mode(miosix::Mode::ALTERNATE); + miso0.alternateFunction(6); + mosi0.mode(miosix::Mode::ALTERNATE); + mosi0.alternateFunction(6); + + cs0.mode(miosix::Mode::OUTPUT); + dio0.mode(miosix::Mode::INPUT); + } + + cs0.high(); + enableExternalInterrupt(dio0.getPort(), dio0.getNumber(), + InterruptTrigger::RISING_EDGE); +} + +/// Initialize stm32f407g board (sx1278[1] only) +void initBoard1() +{ + { + miosix::FastInterruptDisableLock dLock; + + // Enable SPI2 + RCC->APB1ENR |= RCC_APB1ENR_SPI2EN; + RCC_SYNC(); + + sck1.mode(miosix::Mode::ALTERNATE); + sck1.alternateFunction(5); + miso1.mode(miosix::Mode::ALTERNATE); + miso1.alternateFunction(5); + mosi1.mode(miosix::Mode::ALTERNATE); + mosi1.alternateFunction(5); + + cs1.mode(miosix::Mode::OUTPUT); + dio1.mode(miosix::Mode::INPUT); + } + + cs1.high(); + enableExternalInterrupt(dio1.getPort(), dio1.getNumber(), + InterruptTrigger::RISING_EDGE); +} + +void recvLoop(int idx) +{ + char buf[256]; + while (1) + { + if (sx1278[idx]->receive((uint8_t *)buf, sizeof(buf)) != -1) + { + // Make sure there is a terminator somewhere + buf[255] = 0; + printf("[sx1278 @ %p] Received '%s'\n", sx1278[idx], buf); + } + } +} + +void sendLoop(int idx, int interval, char *data) +{ + while (1) + { + miosix::Thread::sleep(interval); + + sx1278[idx]->send((uint8_t *)data, strlen(data) + 1); + printf("[sx1278 @ %p] Sent '%s'\n", sx1278[idx], data); + } +} + +int main() +{ + initBoard0(); + initBoard1(); + + // Run default configuration + SX1278::Config config; + SX1278::Error err; + + // Configure them + sx1278[0] = new SX1278(bus0, cs0); + + printf("\n[sx1278] Configuring sx1278[0]...\n"); + printConfig(config); + if ((err = sx1278[0]->init(config)) != SX1278::Error::NONE) + { + printf("[sx1278] sx1278[0]->init error: %s\n", stringFromErr(err)); + return -1; + } + + sx1278[1] = new SX1278(bus1, cs1); + + printf("\n[sx1278] Configuring sx1278[1]...\n"); + printConfig(config); + if ((err = sx1278[1]->init(config)) != SX1278::Error::NONE) + { + printf("[sx1278] sx1278[1]->init error: %s\n", stringFromErr(err)); + return -1; + } + + // Spawn all threads + std::thread send0( + [=]() { sendLoop(0, 1000, const_cast<char *>("Hi from sx1278[0]!")); }); + std::thread send1( + [=]() { sendLoop(1, 3333, const_cast<char *>("Hi from sx1278[1]!")); }); + + std::thread recv0([]() { recvLoop(0); }); + std::thread recv1([]() { recvLoop(1); }); + + printf("\n[sx1278] Initialization complete!\n"); + + while (1) + miosix::Thread::wait(); + + return 0; +} diff --git a/src/tests/drivers/sx1278/test-sx1278-core.cpp b/src/tests/drivers/sx1278/test-sx1278-core.cpp new file mode 100644 index 0000000000000000000000000000000000000000..86d4bc25445433ae4bfdbad5818197f60ca029e1 --- /dev/null +++ b/src/tests/drivers/sx1278/test-sx1278-core.cpp @@ -0,0 +1,123 @@ +/* Copyright (c) 2021 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 "test-sx1278-core.h" + +using namespace Boardcore; + +const char *stringFromErr(SX1278::Error err) +{ + switch (err) + { + case SX1278::Error::BAD_VALUE: + return "Error::BAD_VALUE"; + + case SX1278::Error::BAD_VERSION: + return "Error::BAD_VERSION"; + + default: + return "<unknown>"; + } +} + +const char *stringFromRxBw(SX1278::RxBw rx_bw) +{ + switch (rx_bw) + { + case SX1278::RxBw::HZ_2600: + return "RxBw::HZ_2600"; + + case SX1278::RxBw::HZ_3100: + return "RxBw::HZ_3100"; + + case SX1278::RxBw::HZ_3900: + return "RxBw::HZ_3900"; + + case SX1278::RxBw::HZ_5200: + return "RxBw::HZ_5200"; + + case SX1278::RxBw::HZ_6300: + return "RxBw::HZ_6300"; + + case SX1278::RxBw::HZ_7800: + return "RxBw::HZ_7800"; + + case SX1278::RxBw::HZ_10400: + return "RxBw::HZ_10400"; + + case SX1278::RxBw::HZ_12500: + return "RxBw::HZ_12500"; + + case SX1278::RxBw::HZ_15600: + return "RxBw::HZ_15600"; + + case SX1278::RxBw::HZ_20800: + return "RxBw::HZ_20800"; + + case SX1278::RxBw::HZ_25000: + return "RxBw::HZ_25000"; + + case SX1278::RxBw::HZ_31300: + return "RxBw::HZ_31300"; + + case SX1278::RxBw::HZ_41700: + return "RxBw::HZ_41700"; + + case SX1278::RxBw::HZ_50000: + return "RxBw::HZ_50000"; + + case SX1278::RxBw::HZ_62500: + return "RxBw::HZ_62500"; + + case SX1278::RxBw::HZ_83300: + return "RxBw::HZ_83300"; + + case SX1278::RxBw::HZ_100000: + return "RxBw::HZ_100000"; + + case SX1278::RxBw::HZ_125000: + return "RxBw::HZ_125000"; + + case SX1278::RxBw::HZ_166700: + return "RxBw::HZ_166700"; + + case SX1278::RxBw::HZ_200000: + return "RxBw::HZ_200000"; + + case SX1278::RxBw::HZ_250000: + return "RxBw::HZ_250000"; + + default: + return "<unknown>"; + } +} + +void printConfig(SX1278::Config config) +{ + printf("config.freq_rf = %d\n", config.freq_rf); + printf("config.freq_dev = %d\n", config.freq_dev); + printf("config.bitrate = %d\n", config.bitrate); + printf("config.rx_bw = %s\n", stringFromRxBw(config.rx_bw)); + printf("config.afc_bw = %s\n", stringFromRxBw(config.afc_bw)); + printf("config.ocp = %d\n", config.ocp); + printf("config.power = %d\n", config.power); +} diff --git a/src/tests/drivers/sx1278/test-sx1278-core.h b/src/tests/drivers/sx1278/test-sx1278-core.h new file mode 100644 index 0000000000000000000000000000000000000000..7a5d224a4f887d899389c0dddbfed8788e6c33d5 --- /dev/null +++ b/src/tests/drivers/sx1278/test-sx1278-core.h @@ -0,0 +1,30 @@ +/* Copyright (c) 2021 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 <drivers/SX1278/SX1278.h> + +const char *stringFromErr(Boardcore::SX1278::Error err); +const char *stringFromRxBw(Boardcore::SX1278::RxBw rx_bw); + +void printConfig(Boardcore::SX1278::Config config); diff --git a/src/tests/drivers/sx1278/test-sx1278-mavlink.cpp b/src/tests/drivers/sx1278/test-sx1278-mavlink.cpp new file mode 100644 index 0000000000000000000000000000000000000000..f7b37f60199d64283bee1a24a6b0267ac28de3bb --- /dev/null +++ b/src/tests/drivers/sx1278/test-sx1278-mavlink.cpp @@ -0,0 +1,162 @@ +/* Copyright (c) 2018 Skyward Experimental Rocketry + * Authors: Alvise de'Faveri Tron, Nuno Barcellos, 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 <drivers/SX1278/SX1278.h> +#include <drivers/interrupt/external_interrupts.h> + +#include "test-sx1278-core.h" + +// Ignore warnings, as we don't want to change third party generated files to +// fix them +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wcast-align" +#pragma GCC diagnostic ignored "-Waddress-of-packed-member" +#include <mavlink_lib/lynx/mavlink.h> +#pragma GCC diagnostic pop + +#include <radio/MavlinkDriver/MavlinkDriver.h> + +using namespace Boardcore; +using namespace miosix; + +static const unsigned int queue_len = 10; +static const unsigned int packet_size = 256; +static const unsigned int silence_after_send = 250; +static const unsigned int max_pkt_age = 1000; +static const unsigned int ping_period = 1000; + +// Mavlink out buffer with 10 packets, 256 bytes each. +using Mav = MavlinkDriver<packet_size, queue_len>; + +Mav* channel; + +SPIBus bus(SPI3); + +GpioPin sck(GPIOC_BASE, 10); +GpioPin miso(GPIOC_BASE, 11); +GpioPin mosi(GPIOC_BASE, 12); +GpioPin cs(GPIOA_BASE, 1); +GpioPin dio(GPIOC_BASE, 15); + +SX1278* sx1278 = nullptr; + +void __attribute__((used)) EXTI15_IRQHandlerImpl() +{ + if (sx1278) + sx1278->handleDioIRQ(); +} + +/// Initialize stm32f407g board. +void initBoard() +{ + { + miosix::FastInterruptDisableLock dLock; + + // Enable SPI3 + RCC->APB1ENR |= RCC_APB1ENR_SPI3EN; + RCC_SYNC(); + + // Setup SPI pins + sck.mode(miosix::Mode::ALTERNATE); + sck.alternateFunction(6); + miso.mode(miosix::Mode::ALTERNATE); + miso.alternateFunction(6); + mosi.mode(miosix::Mode::ALTERNATE); + mosi.alternateFunction(6); + + cs.mode(miosix::Mode::OUTPUT); + dio.mode(miosix::Mode::INPUT); + } + + cs.high(); + enableExternalInterrupt(dio.getPort(), dio.getNumber(), + InterruptTrigger::RISING_EDGE); +} + +/** + * @brief Receive function: print the received message id and send an ACK. + */ +static void onReceive(Mav* channel, const mavlink_message_t& msg) +{ + printf("[TmtcTest] Received message, id: %d! Sending ack\n", msg.msgid); + + // Prepare ack messages + mavlink_message_t ackMsg; + mavlink_msg_ack_tm_pack(1, 1, &ackMsg, msg.msgid, msg.seq); + + // Send the ack back to the sender + bool ackSent = channel->enqueueMsg(ackMsg); + + if (!ackSent) + printf("[Receiver] Could not enqueue ack\n"); +} + +/** + * @brief This test enqueues a ping message every second and replies to every + * received message with an ACK. + */ +int main() +{ + initBoard(); + + SX1278::Config config; + SX1278::Error err; + + sx1278 = new SX1278(bus, cs); + + printf("\n[sx1278] Configuring sx1278...\n"); + printConfig(config); + if ((err = sx1278->init(config)) != SX1278::Error::NONE) + { + printf("[sx1278] sx1278->init error: %s\n", stringFromErr(err)); + return -1; + } + + channel = new Mav(sx1278, &onReceive, silence_after_send, max_pkt_age); + + channel->start(); + + // Send function: enqueue a ping every second + while (1) + { + printf("[TmtcTest] Enqueueing ping\n"); + + // Create a Mavlink message + mavlink_message_t pingMsg; + mavlink_msg_ping_tc_pack(1, 1, &pingMsg, miosix::getTick()); + + // Send the message + bool ackSent = channel->enqueueMsg(pingMsg); + + if (!ackSent) + printf("[TmtcTest] Could not enqueue ping\n"); + + // LED blink + ledOn(); + miosix::delayMs(200); + ledOff(); + + miosix::Thread::sleep(ping_period); + } + + return 0; +} diff --git a/src/tests/drivers/sx1278/test-sx1278-rx.cpp b/src/tests/drivers/sx1278/test-sx1278-rx.cpp new file mode 100644 index 0000000000000000000000000000000000000000..a32b475743e974bc6d64689c58e61692539020eb --- /dev/null +++ b/src/tests/drivers/sx1278/test-sx1278-rx.cpp @@ -0,0 +1,24 @@ +/* Copyright (c) 2021 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. + */ + +#define DISABLE_TX +#include "test-sx1278-bench.cpp" diff --git a/src/tests/drivers/sx1278/test-sx1278-serial.cpp b/src/tests/drivers/sx1278/test-sx1278-serial.cpp new file mode 100644 index 0000000000000000000000000000000000000000..062eb72080c3854a538504825574b32562a88986 --- /dev/null +++ b/src/tests/drivers/sx1278/test-sx1278-serial.cpp @@ -0,0 +1,134 @@ +/* Copyright (c) 2021 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 <drivers/SX1278/SX1278.h> +#include <drivers/interrupt/external_interrupts.h> +#include <filesystem/console/console_device.h> + +#include <thread> + +#include "test-sx1278-core.h" + +using namespace Boardcore; +using namespace miosix; + +SPIBus bus(SPI3); + +GpioPin sck(GPIOC_BASE, 10); +GpioPin miso(GPIOC_BASE, 11); +GpioPin mosi(GPIOC_BASE, 12); +GpioPin cs(GPIOA_BASE, 1); +GpioPin dio(GPIOC_BASE, 15); + +SX1278* sx1278 = nullptr; + +void __attribute__((used)) EXTI15_IRQHandlerImpl() +{ + if (sx1278) + sx1278->handleDioIRQ(); +} + +/// Initialize stm32f407g board. +void initBoard() +{ + { + miosix::FastInterruptDisableLock dLock; + + // Enable SPI3 + RCC->APB1ENR |= RCC_APB1ENR_SPI3EN; + RCC_SYNC(); + + // Setup SPI pins + sck.mode(miosix::Mode::ALTERNATE); + sck.alternateFunction(6); + miso.mode(miosix::Mode::ALTERNATE); + miso.alternateFunction(6); + mosi.mode(miosix::Mode::ALTERNATE); + mosi.alternateFunction(6); + + cs.mode(miosix::Mode::OUTPUT); + dio.mode(miosix::Mode::INPUT); + } + + cs.high(); + enableExternalInterrupt(dio.getPort(), dio.getNumber(), + InterruptTrigger::RISING_EDGE); +} + +void recvLoop() +{ + uint8_t msg[256]; + auto console = miosix::DefaultConsole::instance().get(); + + while (1) + { + int len = sx1278->receive(msg, sizeof(msg)); + if (len > 0) + { + console->writeBlock(msg, len, 0); + // TODO: Flushing? + } + } +} + +void sendLoop() +{ + uint8_t msg[256]; + auto console = miosix::DefaultConsole::instance().get(); + + while (1) + { + int len = console->readBlock(msg, sizeof(msg), 0); + if (len > 0) + { + sx1278->send(msg, len); + } + } +} + +int main() +{ + initBoard(); + + SX1278::Config config; + SX1278::Error err; + + sx1278 = new SX1278(bus, cs); + + printf("\n[sx1278] Configuring sx1278...\n"); + printConfig(config); + if ((err = sx1278->init(config)) != SX1278::Error::NONE) + { + printf("[sx1278] sx1278->init error: %s\n", stringFromErr(err)); + return -1; + } + + std::thread recv([]() { recvLoop(); }); + std::thread send([]() { sendLoop(); }); + + printf("\n[sx1278] Initialization complete!\n"); + + while (1) + miosix::Thread::wait(); + + return 0; +} diff --git a/src/tests/drivers/sx1278/test-sx1278-tx.cpp b/src/tests/drivers/sx1278/test-sx1278-tx.cpp new file mode 100644 index 0000000000000000000000000000000000000000..b332d3accf06a9d21f0c54d30e7ef66612f20db3 --- /dev/null +++ b/src/tests/drivers/sx1278/test-sx1278-tx.cpp @@ -0,0 +1,24 @@ +/* Copyright (c) 2021 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. + */ + +#define DISABLE_RX +#include "test-sx1278-bench.cpp"