diff --git a/src/shared/drivers/i2c/I2CDriver-f7.cpp b/src/shared/drivers/i2c/I2CDriver-f7.cpp index 7c25dca9f8374e7622743bf9ba37ed3fd905a399..412742b2895c5418b9b3bf35eb63739cbdbfc192 100644 --- a/src/shared/drivers/i2c/I2CDriver-f7.cpp +++ b/src/shared/drivers/i2c/I2CDriver-f7.cpp @@ -77,7 +77,7 @@ I2CTimings calculateTimings(uint32_t f, uint32_t fi2c) #if defined(_BOARD_STM32F756ZG_NUCLEO) const uint16_t correction = 10; #elif defined(_BOARD_STM32F767ZI_COMPUTE_UNIT) || \ - defined(_BOARD_STM32F767ZI_GEMINI_GS) || \ + defined(_BOARD_STM32F767ZI_GEMINI_GS) || \ defined(_BOARD_STM32F767ZI_NUCLEO) const uint16_t correction = 7; #else diff --git a/src/shared/radio/SX1278/SX1278Common.cpp b/src/shared/radio/SX1278/SX1278Common.cpp index dba58a3b97944c74fba0d1f4f8f907bbdd012643..a4cc12d11b023225a5504b94801a93956e9772fb 100644 --- a/src/shared/radio/SX1278/SX1278Common.cpp +++ b/src/shared/radio/SX1278/SX1278Common.cpp @@ -81,12 +81,12 @@ ISX1278::IrqFlags SX1278Common::waitForIrq(LockMode &guard, IrqFlags set_irq, } // Check that this hasn't already happened - if ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) != 0) + if ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) != 0) { break; } - if(!waitForIrqInner(guard, unlock)) + if (!waitForIrqInner(guard, unlock)) { // TODO: Something bad happened, do something! } @@ -143,14 +143,16 @@ bool SX1278Common::waitForIrqInner(LockMode &_guard, bool unlock) mutex.unlock(); } - int start = miosix::getTick(); + int start = miosix::getTick(); miosix::TimedWaitResult result = miosix::TimedWaitResult::NoTimeout; { miosix::FastInterruptDisableLock lock; - while (state.irq_wait_thread && result == miosix::TimedWaitResult::NoTimeout) + while (state.irq_wait_thread && + result == miosix::TimedWaitResult::NoTimeout) { - result = miosix::Thread::IRQenableIrqAndTimedWaitMs(lock, start + IRQ_TIMEOUT); + result = miosix::Thread::IRQenableIrqAndTimedWaitMs( + lock, start + IRQ_TIMEOUT); } } diff --git a/src/shared/radio/SX1278/SX1278Lora.cpp b/src/shared/radio/SX1278/SX1278Lora.cpp index de7c3ecfdccddf5ba8df6fb292f7d9d0dc9dd2f1..8e9e76d6afe13091be4a995ab776ab336a665127 100644 --- a/src/shared/radio/SX1278/SX1278Lora.cpp +++ b/src/shared/radio/SX1278/SX1278Lora.cpp @@ -163,7 +163,8 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config) enterLoraMode(); // Then make sure the device remains in standby and not in sleep - setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, InterruptTrigger::RISING_EDGE, false, false); + setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, + InterruptTrigger::RISING_EDGE, false, false); // Lock the bus Lock guard(*this); diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp index caffecc2ef6308573e55ebba14b739df744289de..c36bcf791d6660fd7616e1e642584548f0a702dd 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp @@ -94,10 +94,7 @@ void __attribute__((used)) SX1278_IRQ_DIO3() sx1278->handleDioIRQ(); } -void initBoard() -{ - -} +void initBoard() {} Mav* channel; @@ -154,8 +151,9 @@ int main() std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); - sx1278 = - new SX1278Fsk(bus, cs::getPin(), dio0::getPin(), dio1::getPin(), dio3::getPin(), SPI::ClockDivider::DIV_64, std::move(frontend)); + sx1278 = new SX1278Fsk(bus, cs::getPin(), dio0::getPin(), dio1::getPin(), + dio3::getPin(), 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/sx1278-init.h b/src/tests/radio/sx1278/sx1278-init.h index 9f26bf0796db7ae422d2e366eaf7b73c99d682d7..abd9121b50fcbf1e831bf5dc25be14489845ef04 100644 --- a/src/tests/radio/sx1278/sx1278-init.h +++ b/src/tests/radio/sx1278/sx1278-init.h @@ -22,9 +22,8 @@ #pragma once -#include <miosix.h> - #include <drivers/interrupt/external_interrupts.h> +#include <miosix.h> // SX1278 includes #include <radio/SX1278/SX1278Frontends.h> @@ -92,7 +91,7 @@ using rxen = miosix::radio::rxEn; #define SX1278_IS_SKYWARD433 // Comment to use SX1278_2 -// #define SX1278_1 +#define SX1278_1 #ifdef SX1278_1 using cs = miosix::radio1::cs; @@ -105,7 +104,7 @@ using miso = miosix::radio1::spi::miso; using mosi = miosix::radio1::spi::mosi; #define SX1278_NRST -using rst = miosix::radio1::nrst; +using rst = miosix::radio1::nrst; #define SX1278_SPI MIOSIX_RADIO1_SPI @@ -123,7 +122,7 @@ using miso = miosix::radio2::spi::miso; using mosi = miosix::radio2::spi::mosi; #define SX1278_NRST -using rst = miosix::radio2::nrst; +using rst = miosix::radio2::nrst; #define SX1278_SPI MIOSIX_RADIO2_SPI @@ -215,6 +214,8 @@ bool initRadio() Boardcore::SX1278Lora::Config config; Boardcore::SX1278Lora::Error err; + config.freq_rf = 444000000; + sx1278 = new Boardcore::SX1278Lora(sx1278_bus, cs::getPin(), dio0::getPin(), dio1::getPin(), dio3::getPin(), Boardcore::SPI::ClockDivider::DIV_64, @@ -233,6 +234,8 @@ bool initRadio() Boardcore::SX1278Fsk::Config config; Boardcore::SX1278Fsk::Error err; + config.freq_rf = 444000000; + sx1278 = new Boardcore::SX1278Fsk(sx1278_bus, cs::getPin(), dio0::getPin(), dio1::getPin(), dio3::getPin(), Boardcore::SPI::ClockDivider::DIV_32, diff --git a/src/tests/radio/sx1278/test-sx1278-bench-serial.cpp b/src/tests/radio/sx1278/test-sx1278-bench-serial.cpp index 0453afc3111c313633cc04c19561ef7b52102125..da250f7fe9a41c8f0e32429471d9a092515f69c6 100644 --- a/src/tests/radio/sx1278/test-sx1278-bench-serial.cpp +++ b/src/tests/radio/sx1278/test-sx1278-bench-serial.cpp @@ -47,15 +47,17 @@ int main() "RSSI: %.2f dBm\n" "FEI: %.2f Hz\n" "SNR: %.2f\n" - "%d %d %d\n", + "dio0: %d\n" + "dio1: %d\n" + "dio3: %d\n", static_cast<float>(stats.txBitrate()) / 1000.0f, stats.sent_count, static_cast<float>(stats.rxBitrate()) / 1000.0f, stats.recv_count, - stats.corrupted_count, stats.rssi, stats.fei, stats.snr, dio0_cnt, dio1_cnt, dio3_cnt); + stats.corrupted_count, stats.rssi, stats.fei, stats.snr, dio0_cnt, + dio1_cnt, dio3_cnt); dio0_cnt = 0; dio1_cnt = 0; dio3_cnt = 0; - miosix::Thread::sleep(2000); }