diff --git a/CMakeLists.txt b/CMakeLists.txt index 32c94c6923756a95a03ab1a667ea03b535f0b72a..ad794b6f0220f7347b1ac0fb5ae15c7b63e1db63 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -245,29 +245,23 @@ 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-bench src/tests/drivers/sx1278/test-sx1278-bench.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-bidir src/tests/drivers/sx1278/test-sx1278-bidir.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-bidir-gs src/tests/drivers/sx1278/test-sx1278-bidir.cpp) +sbs_target(test-sx1278-bidir-gs stm32f429zi_skyward_ground_station) -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-bidir-v3 src/tests/drivers/sx1278/test-sx1278-bidir.cpp) +sbs_target(test-sx1278-bidir-v3 stm32f429zi_skyward_death_stack_v3) + +add_executable(test-sx1278-tx src/tests/drivers/sx1278/test-sx1278-tx.cpp) +sbs_target(test-sx1278-tx stm32f429zi_skyward_death_stack_v3) + +add_executable(test-sx1278-rx src/tests/drivers/sx1278/test-sx1278-rx.cpp) +sbs_target(test-sx1278-rx stm32f429zi_skyward_ground_station) add_executable(test-sx1278-mavlink src/tests/drivers/sx1278/test-sx1278-mavlink.cpp diff --git a/src/tests/drivers/sx1278/test-sx1278-bench.cpp b/src/tests/drivers/sx1278/test-sx1278-bench.cpp index 31db75f4f5c47aa0a847be004e403718df858116..0e1307a9c696f755d340755c273c5a1636b1e65d 100644 --- a/src/tests/drivers/sx1278/test-sx1278-bench.cpp +++ b/src/tests/drivers/sx1278/test-sx1278-bench.cpp @@ -25,50 +25,58 @@ #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) - */ +struct Stats; -SPIBus bus0(SPI3); -SPIBus bus1(SPI2); +const char *stringFromErr(SX1278::Error err) +{ + switch (err) + { + case SX1278::Error::BAD_VALUE: + return "Error::BAD_VALUE"; -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); + case SX1278::Error::BAD_VERSION: + return "Error::BAD_VERSION"; -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); + default: + return "<unknown>"; + } +} -struct Stats; +#if defined _BOARD_STM32F429ZI_SKYWARD_GS +#include "interfaces-impl/hwmapping.h" + +#if 1 // use ra01 +using cs = peripherals::ra01::cs; +using dio0 = peripherals::ra01::dio0; +#else +using cs = peripherals::sx127x::cs; +using dio0 = peripherals::sx127x::dio0; +#endif + +using sck = interfaces::spi4::sck; +using miso = interfaces::spi4::miso; +using mosi = interfaces::spi4::mosi; + +#define SX1278_SPI SPI4 -const char *stringFromErr(SX1278::Error err); -const char *stringFromRxBw(SX1278::RxBw rx_bw); +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 +#include "interfaces-impl/hwmapping.h" -void printStats(Stats stats); +using cs = sensors::sx127x::cs; +using dio0 = sensors::sx127x::dio0; + +using sck = interfaces::spi5::sck; +using miso = interfaces::spi5::miso; +using mosi = interfaces::spi5::mosi; + +#define SX1278_SPI SPI5 + +#else +#error "Target not supported" +#endif /// Status informations. struct Stats @@ -91,9 +99,23 @@ struct Stats } } + void print() const + { + // Prints are REALLY slow, so take a COPY of stats, so we can print an + // instant in time. + Stats stats = *this; + + 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); + } + } stats; -SX1278 *sx1278[2] = {nullptr, nullptr}; +SX1278 *sx1278 = nullptr; struct Msg { @@ -107,14 +129,14 @@ struct Msg const static int DUMMY_3 = 0x1234abcd; }; -void recvLoop(int idx) +void recvLoop() { while (1) { Msg msg; memset(&msg, 0, sizeof(msg)); - int len = sx1278[idx]->receive((uint8_t *)&msg, sizeof(msg)); + int len = sx1278->receive((uint8_t *)&msg, sizeof(msg)); if (len != sizeof(msg)) { @@ -134,7 +156,7 @@ void recvLoop(int idx) } } -void sendLoop(int idx) +void sendLoop() { while (1) { @@ -146,7 +168,7 @@ void sendLoop(int idx) msg.dummy_2 = Msg::DUMMY_2; msg.dummy_3 = Msg::DUMMY_3; - sx1278[idx]->send((uint8_t *)&msg, sizeof(msg)); + sx1278->send((uint8_t *)&msg, sizeof(msg)); stats.send_count = next_idx; } } @@ -154,116 +176,57 @@ void sendLoop(int 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 defined _BOARD_STM32F429ZI_SKYWARD_GS +void __attribute__((used)) EXTI6_IRQHandlerImpl() +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 +void __attribute__((used)) EXTI10_IRQHandlerImpl() +#else +#error "Target not supported" +#endif { - if (sx1278[1]) - sx1278[1]->handleDioIRQ(); + if (sx1278) + sx1278->handleDioIRQ(); } -/// Initialize stm32f407g board (sx1278[0] only) -void initBoard0() +void initBoard() { - { - 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(), +#if defined _BOARD_STM32F429ZI_SKYWARD_GS + enableExternalInterrupt(GPIOF_BASE, 6, 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(), +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 + enableExternalInterrupt(GPIOF_BASE, 10, InterruptTrigger::RISING_EDGE); +#else +#error "Target not supported" +#endif } int main() { -#ifndef DISABLE_RX - initBoard0(); -#endif -#ifndef DISABLE_TX - initBoard1(); -#endif + initBoard(); // Run default configuration SX1278::Config config; SX1278::Error err; - // Configure them -#ifndef DISABLE_RX - sx1278[0] = new SX1278(bus0, cs0); + SPIBus bus(SX1278_SPI); + GpioPin cs = cs::getPin(); - 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 + sx1278 = new SX1278(bus, cs); -#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("\n[sx1278] Configuring sx1278...\n"); + if ((err = sx1278->init(config)) != SX1278::Error::NONE) { - printf("[sx1278] sx1278[1]->init error: %s\n", stringFromErr(err)); + printf("[sx1278] sx1278->init error: %s\n", stringFromErr(err)); return -1; } -#endif // Run background threads #ifndef DISABLE_RX - std::thread recv([]() { recvLoop(0); }); + std::thread recv([]() { recvLoop(); }); #endif #ifndef DISABLE_TX - miosix::Thread::sleep(500); - std::thread send([]() { sendLoop(1); }); + std::thread send([]() { sendLoop(); }); #endif // Finish! @@ -285,7 +248,7 @@ int main() ((float)elapsed / 1000.0f); printf("\n[sx1278] Stats:\n"); - printStats(stats); + stats.print(); printf("tx_bitrate: %.2f kb/s\n", tx_bitrate / 1000.0f); printf("rx_bitrate: %.2f kb/s\n", rx_bitrate / 1000.0f); @@ -294,16 +257,3 @@ int main() 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 index c0cc885bf6c9b84693700cb808e3909f81779045..dd07e00964ca68ea4d7c351f44bb27c37690daaa 100644 --- a/src/tests/drivers/sx1278/test-sx1278-bidir.cpp +++ b/src/tests/drivers/sx1278/test-sx1278-bidir.cpp @@ -22,178 +22,146 @@ #include <drivers/interrupt/external_interrupts.h> #include <radio/SX1278/SX1278.h> +#include <miosix.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) - */ +const char *stringFromErr(SX1278::Error err) +{ + switch (err) + { + case SX1278::Error::BAD_VALUE: + return "Error::BAD_VALUE"; -SPIBus bus0(SPI3); -SPIBus bus1(SPI2); + case SX1278::Error::BAD_VERSION: + return "Error::BAD_VERSION"; -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); + default: + return "<unknown>"; + } +} -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); +#if defined _BOARD_STM32F429ZI_SKYWARD_GS +#include "interfaces-impl/hwmapping.h" -SX1278 *sx1278[2] = {nullptr, nullptr}; +#if 1 // use ra01 +using cs = peripherals::ra01::cs; +using dio0 = peripherals::ra01::dio0; +#else +using cs = peripherals::sx127x::cs; +using dio0 = peripherals::sx127x::dio0; +#endif -void __attribute__((used)) EXTI15_IRQHandlerImpl() -{ - if (sx1278[0]) - sx1278[0]->handleDioIRQ(); -} +using sck = interfaces::spi4::sck; +using miso = interfaces::spi4::miso; +using mosi = interfaces::spi4::mosi; -void __attribute__((used)) EXTI0_IRQHandlerImpl() -{ - if (sx1278[1]) - sx1278[1]->handleDioIRQ(); -} +#define SX1278_SPI SPI4 -/// 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); - } +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 +#include "interfaces-impl/hwmapping.h" - cs0.high(); - enableExternalInterrupt(dio0.getPort(), dio0.getNumber(), - InterruptTrigger::RISING_EDGE); -} +using cs = sensors::sx127x::cs; +using dio0 = sensors::sx127x::dio0; -/// Initialize stm32f407g board (sx1278[1] only) -void initBoard1() -{ - { - miosix::FastInterruptDisableLock dLock; +using sck = interfaces::spi5::sck; +using miso = interfaces::spi5::miso; +using mosi = interfaces::spi5::mosi; - // Enable SPI2 - RCC->APB1ENR |= RCC_APB1ENR_SPI2EN; - RCC_SYNC(); +#define SX1278_SPI SPI5 - sck1.mode(miosix::Mode::ALTERNATE); - sck1.alternateFunction(5); - miso1.mode(miosix::Mode::ALTERNATE); - miso1.alternateFunction(5); - mosi1.mode(miosix::Mode::ALTERNATE); - mosi1.alternateFunction(5); +#else +#error "Target not supported" +#endif - cs1.mode(miosix::Mode::OUTPUT); - dio1.mode(miosix::Mode::INPUT); - } +SX1278 *sx1278 = nullptr; + +#if defined _BOARD_STM32F429ZI_SKYWARD_GS +void __attribute__((used)) EXTI6_IRQHandlerImpl() +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 +void __attribute__((used)) EXTI10_IRQHandlerImpl() +#else +#error "Target not supported" +#endif +{ + if (sx1278) + sx1278->handleDioIRQ(); +} - cs1.high(); - enableExternalInterrupt(dio1.getPort(), dio1.getNumber(), +void initBoard() +{ +#if defined _BOARD_STM32F429ZI_SKYWARD_GS + enableExternalInterrupt(GPIOF_BASE, 6, + InterruptTrigger::RISING_EDGE); +#elif defined _BOARD_STM32F429ZI_SKYWARD_DEATHST_V3 + enableExternalInterrupt(GPIOF_BASE, 10, InterruptTrigger::RISING_EDGE); +#else +#error "Target not supported" +#endif } -void recvLoop(int idx) +void recvLoop() { - char buf[256]; + char buf[64]; while (1) { - if (sx1278[idx]->receive((uint8_t *)buf, sizeof(buf)) != -1) + ssize_t res = sx1278->receive((uint8_t *)buf, sizeof(buf)); + if (res != -1) { // Make sure there is a terminator somewhere - buf[255] = 0; - printf("[sx1278 @ %p] Received '%s'\n", sx1278[idx], buf); + buf[res] = 0; + printf("[sx1278] Received '%s'\n", buf); } } } -void sendLoop(int idx, int interval, char *data) +void sendLoop(int interval, const char *data) { + char buf[64]; + strncpy(buf, data, sizeof(buf) - 1); + while (1) { miosix::Thread::sleep(interval); - sx1278[idx]->send((uint8_t *)data, strlen(data) + 1); - printf("[sx1278 @ %p] Sent '%s'\n", sx1278[idx], data); + sx1278->send((uint8_t *)buf, strlen(buf) + 1); + printf("[sx1278] Sent '%s'\n", buf); } } int main() { - initBoard0(); - initBoard1(); + initBoard(); // Run default configuration SX1278::Config config; SX1278::Error err; - // Configure them - sx1278[0] = new SX1278(bus0, cs0); + SPIBus bus(SX1278_SPI); + GpioPin cs = cs::getPin(); - 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 = new SX1278(bus, cs); - 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("\n[sx1278] Configuring sx1278...\n"); + if ((err = sx1278->init(config)) != SX1278::Error::NONE) { - printf("[sx1278] sx1278[1]->init error: %s\n", stringFromErr(err)); + printf("[sx1278] sx1278->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); }); + std::thread send([]() { sendLoop(1000, "DIO0 (suca palle)"); }); + std::thread recv([]() { recvLoop(); }); printf("\n[sx1278] Initialization complete!\n"); + // sx1278->debugDumpRegisters(); + while (1) miosix::Thread::wait();