Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found
Select Git revision

Target

Select target project
  • avn/swd/skyward-boardcore
  • emilio.corigliano/skyward-boardcore
  • ettore.pane/skyward-boardcore
  • giulia.facchi/skyward-boardcore
  • valerio.flamminii/skyward-boardcore
  • nicolo.caruso/skyward-boardcore
6 results
Select Git revision
Show changes
Showing with 1040 additions and 912 deletions
......@@ -33,6 +33,7 @@
#include <tscpp/buffer.h>
#include <utils/Debug.h>
#include <chrono>
#include <fstream>
#include <stdexcept>
......@@ -287,8 +288,8 @@ void Logger::writeThread()
return;
// Write data to disk
Timer timer;
timer.start();
using namespace std::chrono;
auto start = system_clock::now();
size_t result = fwrite(buffer->data, 1, buffer->size, file);
if (result != buffer->size)
......@@ -301,8 +302,9 @@ void Logger::writeThread()
else
stats.buffersWritten++;
timer.stop();
stats.averageWriteTime = timer.interval();
auto interval = system_clock::now() - start;
stats.averageWriteTime =
duration_cast<milliseconds>(interval).count();
stats.maxWriteTime =
max(stats.maxWriteTime, stats.averageWriteTime);
......
......@@ -42,6 +42,8 @@ implementation before including MavlinkDriver.h"
#include <radio/Transceiver.h>
#include <utils/collections/SyncPacketQueue.h>
#include <functional>
#include "MavlinkStatus.h"
namespace Boardcore
......
......@@ -23,6 +23,7 @@
#include "SX1278Common.h"
#include <kernel/scheduler/scheduler.h>
#include <utils/KernelTime.h>
namespace Boardcore
{
......@@ -30,9 +31,9 @@ namespace Boardcore
namespace SX1278
{
void SX1278Common::handleDioIRQ(Dio dio)
void SX1278Common::handleDioIRQ()
{
if (state.waiting_dio_mask.test(dio) && state.irq_wait_thread)
if (state.irq_wait_thread)
{
state.irq_wait_thread->IRQwakeup();
if (state.irq_wait_thread->IRQgetPriority() >
......@@ -45,75 +46,72 @@ void SX1278Common::handleDioIRQ(Dio dio)
}
}
void SX1278Common::enableIrqs()
{
enableExternalInterrupt(dio0, InterruptTrigger::RISING_EDGE);
enableExternalInterrupt(dio1, InterruptTrigger::RISING_EDGE);
enableExternalInterrupt(dio3, InterruptTrigger::RISING_EDGE);
}
void SX1278Common::disableIrqs()
{
disableExternalInterrupt(dio0);
disableExternalInterrupt(dio1);
disableExternalInterrupt(dio3);
}
void SX1278Common::setDefaultMode(Mode mode, DioMapping mapping,
InterruptTrigger dio1_trigger,
bool tx_frontend, bool rx_frontend)
{
mutex.lock();
enterMode(mode, mapping, tx_frontend, rx_frontend);
mutex.unlock();
miosix::Lock<miosix::FastMutex> lock(mutex);
enterMode(mode, mapping, dio1_trigger, tx_frontend, rx_frontend);
}
void SX1278Common::waitForIrq(LockMode &_guard, IrqFlags irq, bool unlock)
ISX1278::IrqFlags SX1278Common::waitForIrq(LockMode &guard, IrqFlags set_irq,
IrqFlags reset_irq, bool unlock)
{
// Take a reference to a _guard to MAKE SURE that the mutex is locked, but
// otherwise don't do anything with it
(void)_guard;
// Convert the IRQ mask into a DIO mask
DioMask waiting_dio_mask =
getDioMaskFromIrqFlags(irq, state.mode, state.mapping);
IrqFlags ret_irq = 0;
do
{
// An interrupt could occur and read from this variables
{
miosix::FastInterruptDisableLock dLock;
state.waiting_dio_mask = waiting_dio_mask;
miosix::FastInterruptDisableLock lock;
state.irq_wait_thread = miosix::Thread::IRQgetCurrentThread();
}
// Check that this hasn't already happened
if (checkForIrqAndReset(irq))
if ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) != 0)
{
return;
break;
}
if (unlock)
if (!waitForIrqInner(guard, unlock))
{
mutex.unlock();
// TODO: Something bad happened, do something!
}
{
miosix::FastInterruptDisableLock dLock;
while (state.irq_wait_thread)
{
miosix::Thread::IRQwait();
{
miosix::FastInterruptEnableLock eLock(dLock);
miosix::Thread::yield();
}
}
}
// Regain ownership of the lock
if (unlock)
{
mutex.lock();
}
// TODO: Check state of the device, and reset if needed!
// Protect against sporadic IRQs
} while (!checkForIrqAndReset(irq));
} while ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) == 0);
return ret_irq;
}
bool SX1278Common::waitForIrqBusy(LockMode &_guard, IrqFlags irq, int timeout)
ISX1278::IrqFlags SX1278Common::waitForIrqBusy(LockMode &_guard,
IrqFlags set_irq,
IrqFlags reset_irq, int timeout)
{
// Take a reference to a _guard to MAKE SURE that the mutex is locked, but
// otherwise don't do anything with it
(void)_guard;
long long start = miosix::getTick();
long long start = Kernel::getOldTick();
IrqFlags ret_irq = 0;
while ((miosix::getTick() - start) < timeout)
while ((Kernel::getOldTick() - start) < timeout)
{
// Delay between polls
const unsigned int DELAY = 100;
......@@ -121,44 +119,81 @@ bool SX1278Common::waitForIrqBusy(LockMode &_guard, IrqFlags irq, int timeout)
// Tight loop on IRQ register
for (unsigned int i = 0; i < 1000 / DELAY; i++)
{
if (checkForIrqAndReset(irq))
// Check if some of the interrupts triggered
if ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) != 0)
{
return true;
return ret_irq;
}
miosix::delayUs(DELAY);
}
}
return false;
return 0;
}
bool SX1278Common::checkForIrqAndReset(IrqFlags irq)
bool SX1278Common::waitForIrqInner(LockMode &_guard, bool unlock)
{
IrqFlags cur_irq = getIrqFlags();
if (cur_irq & irq)
// Take a reference to a _guard to MAKE SURE that the mutex is locked, but
// otherwise don't do anything with it
(void)_guard;
// Release the lock for others to take
if (unlock)
{
// Reset all of the interrupts we have detected
resetIrqFlags(cur_irq & irq);
mutex.unlock();
}
int start = Kernel::getOldTick();
miosix::TimedWaitResult result = miosix::TimedWaitResult::NoTimeout;
return true;
{
miosix::FastInterruptDisableLock lock;
while (state.irq_wait_thread &&
result == miosix::TimedWaitResult::NoTimeout)
{
result = Kernel::Thread::IRQenableIrqAndTimedWaitMs(
lock, start + IRQ_TIMEOUT);
}
else
}
// Regain ownership of the lock
if (unlock)
{
return false;
mutex.lock();
}
// Check that we didn't have a timeout
return result == miosix::TimedWaitResult::NoTimeout;
}
ISX1278::IrqFlags SX1278Common::checkForIrqAndReset(IrqFlags set_irq,
IrqFlags reset_irq)
{
IrqFlags cur_irq = getIrqFlags();
if (cur_irq & set_irq)
{
// Reset all of the interrupts we have detected
resetIrqFlags(cur_irq & set_irq);
}
return (cur_irq & set_irq) | (~cur_irq & reset_irq);
}
ISX1278Frontend &SX1278Common::getFrontend() { return *frontend; }
SPISlave &SX1278Common::getSpiSlave() { return slave; }
SX1278Common::DeviceState SX1278Common::lockMode(Mode mode, DioMapping mapping,
InterruptTrigger dio1_trigger,
bool tx_frontend,
bool rx_frontend)
{
// Store previous state
DeviceState old_state = state;
enterMode(mode, mapping, tx_frontend, rx_frontend);
enterMode(mode, mapping, dio1_trigger, tx_frontend, rx_frontend);
state.irq_wait_thread = nullptr;
state.waiting_dio_mask = DioMask();
return old_state;
}
......@@ -167,9 +202,8 @@ void SX1278Common::unlockMode(DeviceState old_state)
{
// Do this copy manually, we want stuff to be copied in a specific order
state.irq_wait_thread = old_state.irq_wait_thread;
state.waiting_dio_mask = old_state.waiting_dio_mask;
enterMode(old_state.mode, old_state.mapping, old_state.is_tx_frontend_on,
old_state.is_rx_frontend_on);
enterMode(old_state.mode, old_state.mapping, old_state.dio1_trigger,
old_state.is_tx_frontend_on, old_state.is_rx_frontend_on);
}
void SX1278Common::lock() { mutex.lock(); }
......@@ -177,6 +211,7 @@ void SX1278Common::lock() { mutex.lock(); }
void SX1278Common::unlock() { mutex.unlock(); }
void SX1278Common::enterMode(Mode mode, DioMapping mapping,
InterruptTrigger dio1_trigger,
bool set_tx_frontend_on, bool set_rx_frontend_on)
{
// disable - enable in order to avoid having both RX/TX frontends active at
......@@ -185,35 +220,41 @@ void SX1278Common::enterMode(Mode mode, DioMapping mapping,
// First disable all of the frontend if necessary
if (set_tx_frontend_on != state.is_tx_frontend_on && !set_tx_frontend_on)
{
disableTxFrontend();
getFrontend().disableTx();
}
if (set_rx_frontend_on != state.is_rx_frontend_on && !set_rx_frontend_on)
{
disableRxFrontend();
getFrontend().disableRx();
}
// Then enable the newly requested ones
if (set_tx_frontend_on != state.is_tx_frontend_on && set_tx_frontend_on)
{
enableTxFrontend();
getFrontend().enableTx();
}
if (set_rx_frontend_on != state.is_rx_frontend_on && set_rx_frontend_on)
{
enableRxFrontend();
getFrontend().enableRx();
}
state.is_tx_frontend_on = set_tx_frontend_on;
state.is_rx_frontend_on = set_rx_frontend_on;
// Check if necessary
if (mode != state.mode)
{
setMode(mode);
state.mode = mode;
}
// Change DIO1 interrupt kind
if (dio1_trigger != state.dio1_trigger)
{
changeInterruptTrigger(dio1, dio1_trigger);
state.dio1_trigger = dio1_trigger;
}
// Finally setup DIO mapping
if (mapping != state.mapping)
{
......
......@@ -22,10 +22,14 @@
#pragma once
#include <drivers/interrupt/external_interrupts.h>
#include <drivers/spi/SPIDriver.h>
#include <miosix.h>
#include <radio/Transceiver.h>
#include <cmath>
#include <memory>
#include "SX1278Defs.h"
namespace Boardcore
......@@ -34,32 +38,31 @@ namespace Boardcore
namespace SX1278
{
using DioMapping = RegDioMapping::Mapping;
/**
* @brief Represents a set of Dio
* @brief Shared interface between all SX1278 drivers
*/
class DioMask
class ISX1278 : public Transceiver
{
public:
DioMask() : mask(0) {}
bool test(Dio dio) const
{
return (mask & (1 << static_cast<int>(dio))) != 0;
}
void set(Dio dio) { mask |= (1 << static_cast<int>(dio)); }
void reset(Dio dio) { mask &= ~(1 << static_cast<int>(dio)); }
private:
uint8_t mask;
};
/**
* @brief Get the RSSI in dBm, during last packet receive.
*/
virtual float getLastRxRssi() = 0;
using DioMapping = RegDioMapping::Mapping;
/**
* @brief Get the frequency error index in Hz, during last packet receive
* (NaN if not available).
*/
virtual float getLastRxFei() { return std::nanf(""); }
/**
* @brief Shared interface between all SX1278 drivers
* @brief Get the signal to noise ratio, during last packet receive (NaN if
* not available).
*/
class ISX1278 : public Transceiver
{
virtual float getLastRxSnr() { return std::nanf(""); }
protected:
/*
* Stuff used internally by SX1278Common
......@@ -73,14 +76,28 @@ protected:
virtual IrqFlags getIrqFlags() = 0;
virtual void resetIrqFlags(IrqFlags flags) = 0;
};
virtual DioMask getDioMaskFromIrqFlags(IrqFlags flags, Mode mode,
DioMapping mapping) = 0;
/**
* @brief Shared interface between all SX1278 frontends
*/
class ISX1278Frontend
{
public:
/**
* @brief Is this frontend connected to PA_BOOST or RFO_LF/_HF?
*/
virtual bool isOnPaBoost() = 0;
virtual void enableRxFrontend() = 0;
virtual void disableRxFrontend() = 0;
virtual void enableTxFrontend() = 0;
virtual void disableTxFrontend() = 0;
/**
* @brief What is the maximum power supported by this frontend?
*/
virtual int maxInPower() = 0;
virtual void enableRx() = 0;
virtual void disableRx() = 0;
virtual void enableTx() = 0;
virtual void disableTx() = 0;
};
class SX1278Common : public ISX1278
......@@ -94,24 +111,35 @@ private:
DioMapping mapping = DioMapping();
// Thread waiting listening for interrupts
miosix::Thread *irq_wait_thread = nullptr;
// What DIOs are we waiting on
DioMask waiting_dio_mask = DioMask();
// True if the RX frontend is enabled
bool is_rx_frontend_on = false;
// True if the TX frontend is enabled
bool is_tx_frontend_on = false;
// Mode of trigger for dio1
InterruptTrigger dio1_trigger = InterruptTrigger::RISING_EDGE;
};
public:
using Dio = SX1278::Dio;
// This is reasonably the maximum we should wait for an interrupt
static constexpr int IRQ_TIMEOUT = 100;
public:
/**
* @brief Handle generic DIO irq.
*/
void handleDioIRQ(Dio dio);
void handleDioIRQ();
protected:
explicit SX1278Common(SPISlave slave) : slave(slave) {}
explicit SX1278Common(SPIBus &bus, miosix::GpioPin cs, miosix::GpioPin dio0,
miosix::GpioPin dio1, miosix::GpioPin dio3,
SPI::ClockDivider clock_divider,
std::unique_ptr<ISX1278Frontend> frontend)
: slave(SPISlave(bus, cs, getSpiBusConfig(clock_divider))), dio0(dio0),
dio1(dio1), dio3(dio3), frontend(std::move(frontend))
{
enableIrqs();
}
~SX1278Common() { disableIrqs(); }
/**
* @brief RAII scoped bus lock guard.
......@@ -134,13 +162,14 @@ protected:
{
public:
LockMode(SX1278Common &driver, Lock &lock, Mode mode,
DioMapping mapping, bool set_tx_frontend_on = false,
DioMapping mapping, InterruptTrigger dio1_trigger,
bool set_tx_frontend_on = false,
bool set_rx_frontend_on = false)
: driver(driver), lock(lock)
{
// cppcheck-suppress useInitializationList
old_state = driver.lockMode(mode, mapping, set_tx_frontend_on,
set_rx_frontend_on);
old_state = driver.lockMode(mode, mapping, dio1_trigger,
set_tx_frontend_on, set_rx_frontend_on);
}
~LockMode() { driver.unlockMode(old_state); }
......@@ -156,44 +185,65 @@ protected:
*
* WARNING: This will lock the mutex.
*/
void setDefaultMode(Mode mode, DioMapping mapping, bool set_tx_frontend_on,
void setDefaultMode(Mode mode, DioMapping mapping,
InterruptTrigger dio1_trigger, bool set_tx_frontend_on,
bool set_rx_frontend_on);
/**
* @brief Wait for generic irq.
*/
void waitForIrq(LockMode &guard, IrqFlags irq, bool unlock = false);
IrqFlags waitForIrq(LockMode &guard, IrqFlags set_irq, IrqFlags reset_irq,
bool unlock = false);
/**
* @brief Busy waits for an interrupt by polling the irq register.
*
* USE ONLY DURING INITIALIZATION! BAD THINGS *HAVE* HAPPENED DUE TO THIS!
*/
bool waitForIrqBusy(LockMode &guard, IrqFlags irq, int timeout);
IrqFlags waitForIrqBusy(LockMode &guard, IrqFlags set_irq,
IrqFlags reset_irq, int timeout);
/**
* @brief Returns if an interrupt happened, and clears it if it did.
* @brief Returns a mask containing triggered interrupts.
*
* NOTE: This function checks both set irqs (rising edge), and reset irqs
* (falling edge). But it only resets set interrupts.
*
* @param set_irq Mask containing set (rising edge) interrupts.
* @param reset_irq Mask containing reset (falling edge) interrupts.
* @return Mask containing all triggered interrupts (both rising and
* falling)
*/
bool checkForIrqAndReset(IrqFlags irq);
IrqFlags checkForIrqAndReset(IrqFlags set_irq, IrqFlags reset_irq);
/**
* @brief The actual SPISlave, used by child classes.
*/
SPISlave slave;
ISX1278Frontend &getFrontend();
SPISlave &getSpiSlave();
private:
DeviceState lockMode(Mode mode, DioMapping mapping, bool set_tx_frontend_on,
void enableIrqs();
void disableIrqs();
bool waitForIrqInner(LockMode &guard, bool unlock);
DeviceState lockMode(Mode mode, DioMapping mapping,
InterruptTrigger dio1_trigger, bool set_tx_frontend_on,
bool set_rx_frontend_on);
void unlockMode(DeviceState old_state);
void lock();
void unlock();
void enterMode(Mode mode, DioMapping mapping, bool set_tx_frontend_on,
bool set_rx_frontend_on);
void enterMode(Mode mode, DioMapping mapping, InterruptTrigger dio1_trigger,
bool set_tx_frontend_on, bool set_rx_frontend_on);
miosix::FastMutex mutex;
DeviceState state;
SPISlave slave;
miosix::GpioPin dio0;
miosix::GpioPin dio1;
miosix::GpioPin dio3;
std::unique_ptr<ISX1278Frontend> frontend;
};
} // namespace SX1278
......
......@@ -22,6 +22,8 @@
#pragma once
#include <drivers/spi/SPIBusInterface.h>
#include <cstdint>
namespace Boardcore
......@@ -40,6 +42,25 @@ constexpr int FXOSC = 32000000;
*/
constexpr float FSTEP = 61.03515625;
inline SPIBusConfig getSpiBusConfig(SPI::ClockDivider clock_divider)
{
SPIBusConfig bus_config = {};
bus_config.clockDivider = clock_divider;
bus_config.mode = SPI::Mode::MODE_0;
bus_config.bitOrder = SPI::Order::MSB_FIRST;
bus_config.byteOrder = SPI::Order::MSB_FIRST;
bus_config.writeBit = SPI::WriteBit::INVERTED;
bus_config.csHoldTimeUs = 3;
return bus_config;
}
constexpr int MIN_FREQ_DEV = 0;
constexpr int MAX_FREQ_DEV = 0x3fff * FSTEP;
constexpr int MIN_FREQ_RF = 0;
constexpr int MAX_FREQ_RF = 0xffffff * FSTEP;
/**
* @brief Represents a DIO..
*/
......@@ -121,20 +142,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,
......@@ -145,94 +158,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 RegPaConfig
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 RegPaRamp
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 RegOcp
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 : 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 RegRxBw
namespace RegAfcBw
{
using RxBwAfc = Boardcore::SX1278::Fsk::RegRxBw::RxBw;
inline constexpr uint8_t make(RxBwAfc rx_bw_afc) { return rx_bw_afc; }
} // namespace RegAfcBw
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
......@@ -240,29 +356,52 @@ 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 RegFifoThresh
namespace RegIrqFlags
{
......@@ -295,22 +434,10 @@ enum PaDac
PA_DAC_DEFAULT_VALUE = 0x04,
PA_DAC_PA_BOOST = 0x07
};
}
namespace RegImageCal
{
constexpr uint8_t AUTO_IMAGE_CAL_ON = 0x80;
inline constexpr uint8_t make(PaDac pa_dac) { return pa_dac | (0x10 << 3); }
enum TempTreshold
{
TEMP_TRESHOLD_5DEG = 0x00,
TEMP_TRESHOLD_10DEG = 0x02,
TEMP_TRESHOLD_15DEG = 0x04,
TEMP_TRESHOLD_20DEG = 0x06,
};
constexpr uint8_t TEMP_MONITOR_OFF = 0x01;
} // namespace RegImageCal
} // namespace RegPaDac
enum Registers
{
......@@ -413,134 +540,6 @@ enum Registers
REG_AGC_PILL = 0x70,
};
static constexpr int DIO_MAPPINGS[6][8][4] =
{[0] =
{
[RegOpMode::MODE_SLEEP] = {0, 0, 0, 0},
[RegOpMode::MODE_STDBY] = {0, 0, 0, RegIrqFlags::LOW_BAT},
[RegOpMode::MODE_FSTX] = {0, 0, 0, RegIrqFlags::LOW_BAT},
[RegOpMode::MODE_TX] = {RegIrqFlags::PACKET_SENT, 0, 0,
RegIrqFlags::LOW_BAT},
[RegOpMode::MODE_FSRX] = {0, 0, 0, RegIrqFlags::LOW_BAT},
[RegOpMode::MODE_RX] =
{RegIrqFlags::PAYLOAD_READY, RegIrqFlags::CRC_OK, 0,
RegIrqFlags::LOW_BAT},
},
[1] =
{
[RegOpMode::MODE_SLEEP] = {RegIrqFlags::FIFO_LEVEL,
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_FULL, 0},
[RegOpMode::MODE_STDBY] = {RegIrqFlags::FIFO_LEVEL,
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_FULL, 0},
[RegOpMode::MODE_FSTX] =
{RegIrqFlags::FIFO_LEVEL, RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_FULL, 0},
[RegOpMode::MODE_TX] = {RegIrqFlags::FIFO_LEVEL,
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_FULL, 0},
[RegOpMode::MODE_FSRX] =
{RegIrqFlags::FIFO_LEVEL, RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_FULL, 0},
[RegOpMode::MODE_RX] = {RegIrqFlags::FIFO_LEVEL,
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_FULL, 0},
},
[2] =
{
[RegOpMode::MODE_SLEEP] =
{RegIrqFlags::FIFO_FULL, 0, RegIrqFlags::FIFO_FULL,
RegIrqFlags::FIFO_FULL},
[RegOpMode::MODE_STDBY] =
{RegIrqFlags::FIFO_FULL, 0, RegIrqFlags::FIFO_FULL,
RegIrqFlags::FIFO_FULL},
[RegOpMode::MODE_FSTX] = {RegIrqFlags::FIFO_FULL, 0,
RegIrqFlags::FIFO_FULL,
RegIrqFlags::FIFO_FULL},
[RegOpMode::MODE_TX] =
{RegIrqFlags::FIFO_FULL, 0, RegIrqFlags::FIFO_FULL,
RegIrqFlags::FIFO_FULL},
[RegOpMode::MODE_FSRX] = {RegIrqFlags::FIFO_FULL, 0,
RegIrqFlags::FIFO_FULL,
RegIrqFlags::FIFO_FULL},
[RegOpMode::MODE_RX] =
{RegIrqFlags::FIFO_FULL, RegIrqFlags::RX_READY,
RegIrqFlags::TIMEOUT, RegIrqFlags::SYNC_ADDRESS_MATCH},
},
[3] =
{
[RegOpMode::MODE_SLEEP] =
{
RegIrqFlags::FIFO_EMPTY,
0,
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_EMPTY,
},
[RegOpMode::MODE_STDBY] =
{
RegIrqFlags::FIFO_EMPTY,
0,
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_EMPTY,
},
[RegOpMode::MODE_FSTX] =
{
RegIrqFlags::FIFO_EMPTY,
0,
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_EMPTY,
},
[RegOpMode::MODE_TX] =
{
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::TX_READY,
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_EMPTY,
},
[RegOpMode::MODE_FSRX] =
{
RegIrqFlags::FIFO_EMPTY,
0,
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_EMPTY,
},
[RegOpMode::MODE_RX] =
{
RegIrqFlags::FIFO_EMPTY,
0,
RegIrqFlags::FIFO_EMPTY,
RegIrqFlags::FIFO_EMPTY,
},
},
[4] =
{
[RegOpMode::MODE_SLEEP] = {0, 0, 0, 0},
[RegOpMode::MODE_STDBY] = {RegIrqFlags::LOW_BAT, 0, 0, 0},
[RegOpMode::MODE_FSTX] = {RegIrqFlags::LOW_BAT,
RegIrqFlags::PILL_LOCK, 0, 0},
[RegOpMode::MODE_TX] = {RegIrqFlags::LOW_BAT,
RegIrqFlags::PILL_LOCK, 0, 0},
[RegOpMode::MODE_FSRX] = {RegIrqFlags::LOW_BAT,
RegIrqFlags::PILL_LOCK, 0, 0},
[RegOpMode::MODE_RX] =
{RegIrqFlags::LOW_BAT, RegIrqFlags::PILL_LOCK,
RegIrqFlags::TIMEOUT,
RegIrqFlags::RSSI | RegIrqFlags::PREAMBLE_DETECT},
},
[5] = {
[RegOpMode::MODE_SLEEP] = {0, 0, 0, 0},
[RegOpMode::MODE_STDBY] = {0, 0, 0, RegIrqFlags::MODE_READY},
[RegOpMode::MODE_FSTX] = {0, RegIrqFlags::PILL_LOCK, 0,
RegIrqFlags::MODE_READY},
[RegOpMode::MODE_TX] = {0, RegIrqFlags::PILL_LOCK, 0,
RegIrqFlags::MODE_READY},
[RegOpMode::MODE_FSRX] = {0, RegIrqFlags::PILL_LOCK, 0,
RegIrqFlags::MODE_READY},
[RegOpMode::MODE_RX] = {0, RegIrqFlags::PILL_LOCK, 0,
RegIrqFlags::MODE_READY},
}};
} // namespace Fsk
/**
......@@ -803,18 +802,6 @@ enum Registers
REG_AGC_PILL = 0x70,
};
static constexpr int DIO_MAPPINGS[6][4] = {
[0] = {RegIrqFlags::RX_DONE, RegIrqFlags::TX_DONE, RegIrqFlags::CAD_DONE,
0},
[1] = {RegIrqFlags::RX_TIMEOUT, RegIrqFlags::FHSS_CHANGE_CHANNEL,
RegIrqFlags::CAD_DETECTED, 0},
[2] = {RegIrqFlags::FHSS_CHANGE_CHANNEL, RegIrqFlags::FHSS_CHANGE_CHANNEL,
RegIrqFlags::FHSS_CHANGE_CHANNEL, 0},
[3] = {RegIrqFlags::CAD_DONE, RegIrqFlags::VALID_HEADER,
RegIrqFlags::PAYLOAD_CRC_ERROR, 0},
[4] = {RegIrqFlags::CAD_DETECTED, 0, 0, 0},
[5] = {0, 0, 0, 0}};
} // namespace Lora
} // namespace SX1278
......
/* Copyright (c) 2022 Skyward Experimental Rocketry
/* Copyright (c) 2023 Skyward Experimental Rocketry
* Author: Davide Mor
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
......@@ -24,64 +24,58 @@
#include <miosix.h>
#include "SX1278Fsk.h"
#include "SX1278Lora.h"
#include "SX1278Common.h"
namespace Boardcore
{
/**
* @brief Specialized SX1278 driver for the E32 400M30S module
*/
class EbyteFsk : public SX1278Fsk
class EbyteFrontend : public SX1278::ISX1278Frontend
{
public:
EbyteFsk(SPISlave slave, miosix::GpioPin tx_enable,
miosix::GpioPin rx_enable)
: SX1278Fsk(slave), tx_enable(tx_enable), rx_enable(rx_enable)
EbyteFrontend(miosix::GpioPin tx_enable, miosix::GpioPin rx_enable)
: tx_enable(tx_enable), rx_enable(rx_enable)
{
// Make sure both the frontends are disabled!
tx_enable.low();
rx_enable.low();
}
[[nodiscard]] Error configure(const Config &config) override;
bool isOnPaBoost() override { return true; }
int maxInPower() override { return 15; }
private:
void enableRxFrontend() override;
void disableRxFrontend() override;
void enableTxFrontend() override;
void disableTxFrontend() override;
void enableRx() override { rx_enable.high(); }
void disableRx() override { rx_enable.low(); }
void enableTx() override { tx_enable.high(); }
void disableTx() override { tx_enable.low(); }
private:
miosix::GpioPin tx_enable;
miosix::GpioPin rx_enable;
};
/**
* @brief Specialized SX1278 driver for the E32 400M30S module
*/
class EbyteLora : public SX1278Lora
class RA01Frontend : public SX1278::ISX1278Frontend
{
public:
EbyteLora(SPISlave slave, miosix::GpioPin tx_enable,
miosix::GpioPin rx_enable)
: SX1278Lora(slave), tx_enable(tx_enable), rx_enable(rx_enable)
{
// Make sure both the frontends are disabled!
tx_enable.low();
rx_enable.low();
}
RA01Frontend() {}
[[nodiscard]] Error configure(const Config &config) override;
bool isOnPaBoost() override { return true; }
int maxInPower() override { return 17; }
private:
void enableRxFrontend() override;
void disableRxFrontend() override;
void enableTxFrontend() override;
void disableTxFrontend() override;
void enableRx() override {}
void disableRx() override {}
void enableTx() override {}
void disableTx() override {}
};
miosix::GpioPin tx_enable;
miosix::GpioPin rx_enable;
class Skyward433Frontend : public SX1278::ISX1278Frontend
{
public:
Skyward433Frontend() {}
bool isOnPaBoost() override { return false; }
int maxInPower() override { return 15; }
void enableRx() override {}
void disableRx() override {}
void enableTx() override {}
void disableTx() override {}
};
} // namespace Boardcore
\ No newline at end of file
......@@ -24,7 +24,9 @@
#include <kernel/scheduler/scheduler.h>
#include <utils/Debug.h>
#include <utils/KernelTime.h>
#include <cassert>
#include <cmath>
namespace Boardcore
......@@ -33,18 +35,7 @@ namespace Boardcore
using namespace SX1278;
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_TRESHOLD_10DEG;
long long now() { return Kernel::getOldTick(); }
// Enable:
// - PayloadReady, PacketSent on DIO0 (mode 00)
......@@ -57,7 +48,6 @@ SX1278Fsk::Error SX1278Fsk::init(const Config &config)
// First probe for the device
if (!checkVersion())
{
TRACE("[sx1278] Wrong chipid\n");
return Error::BAD_VALUE;
}
......@@ -71,73 +61,198 @@ SX1278Fsk::Error SX1278Fsk::init(const Config &config)
bool SX1278Fsk::checkVersion()
{
Lock guard(*this);
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
return spi.readRegister(REG_VERSION) == 0x12;
uint8_t version = spi.readRegister(REG_VERSION);
if (version == 0x12)
{
return true;
}
else
{
LOG_ERR(logger, "Wrong chip id: {}", version);
return false;
}
}
SX1278Fsk::Error SX1278Fsk::configure(const Config &config)
{
// First cycle the device to bring it into Fsk mode (can only be changed in
// sleep)
setDefaultMode(RegOpMode::MODE_SLEEP, DEFAULT_MAPPING, false, false);
// Make sure the device remains in standby and not in sleep
setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, false, false);
// Check that the configuration is actually valid
bool pa_boost = getFrontend().isOnPaBoost();
int min_power = pa_boost ? 2 : 0;
int max_power = getFrontend().maxInPower();
assert(config.power >= min_power && config.power <= max_power &&
"[sx1278] Configured power invalid for given frontend!");
assert(((config.ocp >= 0 && config.ocp <= 120) ||
(config.ocp >= 130 && config.ocp <= 240)) &&
"[sx1278] Invalid ocp!");
assert(config.freq_dev >= MIN_FREQ_DEV && config.freq_dev <= MAX_FREQ_DEV &&
"[sx1278] Invalid freq_dev!");
assert(config.freq_rf >= MIN_FREQ_RF && config.freq_rf <= MAX_FREQ_RF &&
"[sx1278] Invalid freq_rf");
// First make sure the device is in fsk and in standby
enterFskMode();
// Set default mode to standby, that way we reset the fifo every time we
// enter receive
setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING,
InterruptTrigger::RISING_EDGE, false, false);
miosix::Thread::sleep(1);
// Lock the bus
Lock guard(*this);
LockMode guard_mode(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING);
LockMode guard_mode(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING,
InterruptTrigger::RISING_EDGE);
// This code is unreliable so it got commented out, the datasheet states
// that this triggers during a successful state transition, but for some
// reason, this isn't always the case, and can lead to random failures of
// the driver initialization. Removing it has no side effects, so that is
// what was done.
// if (!waitForIrqBusy(guard_mode, RegIrqFlags::MODE_READY, 0, 1000))
// return Error::IRQ_TIMEOUT;
if (!waitForIrqBusy(guard_mode, RegIrqFlags::MODE_READY, 1000))
return Error::IRQ_TIMEOUT;
int bitrate = config.bitrate;
int freq_dev =
std::max(std::min(config.freq_dev, MAX_FREQ_DEV), MIN_FREQ_DEV);
int freq_rf = std::max(std::min(config.freq_rf, MAX_FREQ_RF), MIN_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 <= 120 ? std::max(std::min(config.ocp, 120), 0)
: std::max(std::min(config.ocp, 240), 130);
int power = std::max(std::min(config.power, max_power), min_power);
RegPaRamp::ModulationShaping shaping =
static_cast<RegPaRamp::ModulationShaping>(config.shaping);
RegPacketConfig1::DcFree dc_free =
static_cast<RegPacketConfig1::DcFree>(config.dc_free);
setBitrate(config.bitrate);
setFreqDev(config.freq_dev);
setFreqRF(config.freq_rf);
crc_enabled = config.enable_crc;
setRxBw(config.rx_bw);
setAfcBw(config.afc_bw);
{
SPITransaction spi(getSpiSlave());
// Setup bitrate
uint16_t bitrate_raw = FXOSC / bitrate;
spi.writeRegister16(REG_BITRATE_MSB, bitrate_raw);
// Setup frequency deviation
uint16_t freq_dev_raw = freq_dev / FSTEP;
spi.writeRegister16(REG_FDEV_MSB, freq_dev_raw & 0x3fff);
setOcp(config.ocp);
// Setup base frequency
uint32_t freq_rf_raw = freq_rf / FSTEP;
spi.writeRegister24(REG_FRF_MSB, freq_rf_raw);
uint8_t sync_word[2] = {0x12, 0xad};
setSyncWord(sync_word, 2);
setPreambleLen(2);
setPa(config.power, config.pa_boost);
setShaping(config.shaping);
// Setup RX bandwidth
spi.writeRegister(REG_RX_BW, RegRxBw::make(rx_bw));
// Setup generic parameters
// Setup afc bandwidth
spi.writeRegister(REG_AFC_BW, RegAfcBw::make(afc_bw));
// Setup reg over-current protection
if (config.ocp == 0)
{
SPITransaction spi(slave);
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);
// Set preamble length
spi.writeRegister16(REG_PREAMBLE_MSB, 2);
// 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.writeRegister(
REG_RX_CONFIG,
RegRxConfig::make(true, true, true, true, false, false, false));
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);
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, true, crc_enabled,
dc_free, RegPacketConfig1::PACKET_FORMAT_VARIABLE_LENGTH));
spi.writeRegister(
REG_PACKET_CONFIG_2,
RegPacketConfig2::make(false, false, false,
RegPacketConfig2::DATA_MODE_PACKET));
// Set maximum payload length
spi.writeRegister(REG_PACKET_PAYLOAD_LENGTH, MTU);
// Setup threshold to half of the fifo
spi.writeRegister(
REG_FIFO_THRESH,
RegFifoThresh::TX_START_CONDITION_FIFO_NOT_EMPTY | 0x0f);
RegFifoThresh::make(
FIFO_LEN / 2,
RegFifoThresh::TX_START_CONDITION_FIFO_NOT_EMPTY));
spi.writeRegister(REG_NODE_ADRS, 0x00);
spi.writeRegister(REG_BROADCAST_ADRS, 0x00);
}
// imageCalibrate();
return Error::NONE;
}
......@@ -145,33 +260,81 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len)
{
Lock guard(*this);
LockMode guard_mode(*this, guard, RegOpMode::MODE_RX, DEFAULT_MAPPING,
false, true);
InterruptTrigger::RISING_EDGE, false, true);
// Save the packet locally, we always want to read it all
uint8_t tmp_pkt[MTU];
uint8_t len = 0;
bool crc_ok;
IrqFlags flags = 0;
do
{
// Special wait for payload ready
waitForIrq(guard_mode, RegIrqFlags::PAYLOAD_READY, true);
crc_ok = false;
uint8_t cur_len = 0;
// Special wait for fifo level/payload ready, release the lock at this
// stage
flags = waitForIrq(guard_mode,
RegIrqFlags::FIFO_LEVEL | RegIrqFlags::PAYLOAD_READY,
0, true);
if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && crc_enabled)
{
crc_ok = checkForIrqAndReset(RegIrqFlags::CRC_OK, 0) != 0;
}
// Record RSSI here, it's where it is the most accurate
last_rx_rssi = getRssi();
// Now first packet bit
{
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
len = spi.readRegister(REG_FIFO);
if (len > max_len)
return -1;
spi.readRegisters(REG_FIFO, pkt, len);
int read_size = std::min((int)len, FIFO_LEN / 2);
// Skip 0 sized read
if (read_size != 0)
spi.readRegisters(REG_FIFO, &tmp_pkt[cur_len], read_size);
cur_len += read_size;
}
// Then read the other chunks
while (cur_len < len)
{
flags = waitForIrq(
guard_mode,
RegIrqFlags::FIFO_LEVEL | RegIrqFlags::PAYLOAD_READY, 0);
if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && crc_enabled)
{
crc_ok = checkForIrqAndReset(RegIrqFlags::CRC_OK, 0) != 0;
}
SPITransaction spi(getSpiSlave());
int read_size = std::min((int)(len - cur_len), FIFO_LEN / 2);
spi.readRegisters(REG_FIFO, &tmp_pkt[cur_len], read_size);
cur_len += read_size;
}
// For some reason this sometimes happen?
} while (len == 0);
if (len > max_len || (!crc_ok && crc_enabled))
{
return -1;
}
// Finally copy the packet to the destination
memcpy(pkt, tmp_pkt, len);
return len;
}
bool SX1278Fsk::send(uint8_t *pkt, size_t len)
{
// Packets longer than FIFO_LEN (-1 for the len byte) are not supported
if (len > MTU)
return false;
......@@ -180,20 +343,42 @@ bool SX1278Fsk::send(uint8_t *pkt, size_t len)
rateLimitTx();
Lock guard(*this);
LockMode guard_mode(*this, guard, RegOpMode::MODE_TX, DEFAULT_MAPPING, true,
false);
LockMode guard_mode(*this, guard, RegOpMode::MODE_TX, DEFAULT_MAPPING,
InterruptTrigger::FALLING_EDGE, true, false);
waitForIrq(guard_mode, RegIrqFlags::TX_READY);
waitForIrq(guard_mode, RegIrqFlags::TX_READY, 0);
// Send first segment
{
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
spi.writeRegister(REG_FIFO, static_cast<uint8_t>(len));
spi.writeRegisters(REG_FIFO, pkt, len);
int write_size = std::min((int)len, FIFO_LEN - 1);
spi.writeRegisters(REG_FIFO, pkt, write_size);
pkt += write_size;
len -= write_size;
}
// Then send the rest using fifo control
while (len > 0)
{
// Wait for FIFO_LEVEL to go down
waitForIrq(guard_mode, 0, RegIrqFlags::FIFO_LEVEL);
SPITransaction spi(getSpiSlave());
int write_size = std::min((int)len, FIFO_LEN / 2);
spi.writeRegisters(REG_FIFO, pkt, write_size);
pkt += write_size;
len -= write_size;
}
// Finally wait for packet sent
// Wait for packet sent
waitForIrq(guard_mode, RegIrqFlags::PACKET_SENT);
waitForIrq(guard_mode, RegIrqFlags::PACKET_SENT, 0);
last_tx = now();
return true;
......@@ -213,6 +398,24 @@ float SX1278Fsk::getCurRssi()
return getRssi();
}
void SX1278Fsk::enterFskMode()
{
Lock guard(*this);
SPITransaction spi(getSpiSlave());
// First enter Fsk sleep
spi.writeRegister(REG_OP_MODE,
RegOpMode::make(RegOpMode::MODE_SLEEP, true,
RegOpMode::MODULATION_TYPE_FSK));
miosix::Thread::sleep(1);
// Then transition to standby
spi.writeRegister(REG_OP_MODE,
RegOpMode::make(RegOpMode::MODE_STDBY, true,
RegOpMode::MODULATION_TYPE_FSK));
miosix::Thread::sleep(1);
}
void SX1278Fsk::rateLimitTx()
{
const long long RATE_LIMIT = 2;
......@@ -224,50 +427,10 @@ void SX1278Fsk::rateLimitTx()
}
}
void SX1278Fsk::imageCalibrate()
{
SPITransaction spi(slave);
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)
{
DioMask dio_mask;
if (DIO_MAPPINGS[0][mode][mapping.getMapping(Dio::DIO0)] & flags)
dio_mask.set(Dio::DIO0);
if (DIO_MAPPINGS[1][mode][mapping.getMapping(Dio::DIO1)] & flags)
dio_mask.set(Dio::DIO1);
if (DIO_MAPPINGS[2][mode][mapping.getMapping(Dio::DIO2)] & flags)
dio_mask.set(Dio::DIO2);
if (DIO_MAPPINGS[3][mode][mapping.getMapping(Dio::DIO3)] & flags)
dio_mask.set(Dio::DIO3);
if (DIO_MAPPINGS[4][mode][mapping.getMapping(Dio::DIO4)] & flags)
dio_mask.set(Dio::DIO4);
if (DIO_MAPPINGS[5][mode][mapping.getMapping(Dio::DIO5)] & flags)
dio_mask.set(Dio::DIO5);
return dio_mask;
}
ISX1278::IrqFlags SX1278Fsk::getIrqFlags()
{
SPITransaction spi(slave);
uint8_t flags_msb = spi.readRegister(REG_IRQ_FLAGS_1);
uint8_t flags_lsb = spi.readRegister(REG_IRQ_FLAGS_2);
return (flags_msb << 8 | flags_lsb);
SPITransaction spi(getSpiSlave());
return spi.readRegister16(REG_IRQ_FLAGS_1);
}
void SX1278Fsk::resetIrqFlags(IrqFlags flags)
......@@ -279,244 +442,39 @@ void SX1278Fsk::resetIrqFlags(IrqFlags flags)
if (flags != 0)
{
SPITransaction spi(slave);
spi.writeRegister(REG_IRQ_FLAGS_1, flags >> 8);
spi.writeRegister(REG_IRQ_FLAGS_2, flags);
SPITransaction spi(getSpiSlave());
spi.writeRegister16(REG_IRQ_FLAGS_1, flags);
}
}
float SX1278Fsk::getRssi()
{
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
return static_cast<float>(spi.readRegister(REG_RSSI_VALUE)) * -0.5f;
uint8_t rssi_raw = spi.readRegister(REG_RSSI_VALUE);
return static_cast<float>(rssi_raw) * -0.5f;
}
float SX1278Fsk::getFei()
{
SPITransaction spi(slave);
// Order of read is important!!
uint8_t fei_msb = spi.readRegister(REG_FEI_MSB);
uint8_t fei_lsb = spi.readRegister(REG_FEI_LSB);
SPITransaction spi(getSpiSlave());
uint16_t fei = (static_cast<uint16_t>(fei_msb) << 8) |
(static_cast<uint16_t>(fei_lsb));
return static_cast<float>(fei) * FSTEP;
uint16_t fei_raw = spi.readRegister16(REG_FEI_MSB);
return static_cast<float>(fei_raw) * FSTEP;
}
void SX1278Fsk::setMode(Mode mode)
{
SPITransaction spi(slave);
spi.writeRegister(REG_OP_MODE, REG_OP_MODE_DEFAULT | mode);
SPITransaction spi(getSpiSlave());
spi.writeRegister(REG_OP_MODE,
RegOpMode::make(static_cast<RegOpMode::Mode>(mode), true,
RegOpMode::MODULATION_TYPE_FSK));
}
void SX1278Fsk::setMapping(SX1278::DioMapping mapping)
{
SPITransaction spi(slave);
spi.writeRegister(REG_DIO_MAPPING_1, mapping.raw >> 8);
spi.writeRegister(REG_DIO_MAPPING_2, mapping.raw);
}
void SX1278Fsk::setBitrate(int bitrate)
{
uint16_t val = FXOSC / bitrate;
// Update values
SPITransaction spi(slave);
spi.writeRegister(REG_BITRATE_MSB, val >> 8);
spi.writeRegister(REG_BITRATE_LSB, val);
}
void SX1278Fsk::setFreqDev(int freq_dev)
{
uint16_t val = freq_dev / FSTEP;
SPITransaction spi(slave);
spi.writeRegister(REG_FDEV_MSB, (val >> 8) & 0x3f);
spi.writeRegister(REG_FDEV_LSB, val);
}
void SX1278Fsk::setFreqRF(int freq_rf)
{
uint32_t val = freq_rf / FSTEP;
// Update values
SPITransaction spi(slave);
spi.writeRegister(REG_FRF_MSB, val >> 16);
spi.writeRegister(REG_FRF_MID, val >> 8);
spi.writeRegister(REG_FRF_LSB, val);
}
void SX1278Fsk::setOcp(int ocp)
{
SPITransaction spi(slave);
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(slave);
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(slave);
spi.writeRegister(REG_RX_BW, static_cast<uint8_t>(rx_bw));
}
void SX1278Fsk::setAfcBw(RxBw afc_bw)
{
SPITransaction spi(slave);
spi.writeRegister(REG_AFC_BW, static_cast<uint8_t>(afc_bw));
}
void SX1278Fsk::setPreambleLen(int len)
{
SPITransaction spi(slave);
spi.writeRegister(REG_PREAMBLE_MSB, len >> 8);
spi.writeRegister(REG_PREAMBLE_LSB, 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(slave);
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);
}
// RA01 modules aren't capable of this, disable it to avoid damaging them
// else
// {
// // Run power amplifier boost at full power
// power = 15;
// spi.writeRegister(REG_PA_CONFIG, MAX_POWER << 4 | power |
// RegPaConfig::PA_SELECT_BOOST);
// spi.writeRegister(REG_PA_DAC, RegPaDac::PA_DAC_PA_BOOST | 0x10 << 3);
// }
}
void SX1278Fsk::setShaping(Shaping shaping)
{
SPITransaction spi(slave);
spi.writeRegister(REG_PA_RAMP, static_cast<uint8_t>(shaping) | 0x09);
}
void SX1278Fsk::debugDumpRegisters()
{
Lock guard(*this);
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(slave);
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++;
}
SPITransaction spi(getSpiSlave());
spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw);
}
} // namespace Boardcore
......@@ -41,36 +41,44 @@ public:
/**
* @brief Maximum transmittable unit of this driver.
*/
static constexpr size_t MTU = SX1278::Fsk::FIFO_LEN - 1;
static constexpr size_t MTU = 255;
/**
* @brief Requested SX1278 configuration.
*/
struct Config
{
/**
* @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,
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,
......@@ -82,6 +90,15 @@ public:
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,
......@@ -89,11 +106,6 @@ public:
WHITENING = SX1278::Fsk::RegPacketConfig1::DC_FREE_WHITENING
};
/**
* @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.
......@@ -101,12 +113,12 @@ 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).
bool pa_boost = true; //< Enable output on PA_BOOST.
Shaping shaping = Shaping::GAUSSIAN_BT_1_0; //< Shaping applied to
// the modulation stream.
DcFree dc_free = DcFree::WHITENING; //< Dc free encoding scheme.
bool enable_crc = true; //< Enable hardware CRC calculation/checking
};
/**
......@@ -122,11 +134,16 @@ public:
/**
* @brief Construct a new SX1278
*
* @param bus SPI bus used.
* @param cs Chip select pin.
*/
explicit SX1278Fsk(SPISlave slave) : SX1278Common(slave) {}
explicit SX1278Fsk(SPIBus &bus, miosix::GpioPin cs, miosix::GpioPin dio0,
miosix::GpioPin dio1, miosix::GpioPin dio3,
SPI::ClockDivider clock_divider,
std::unique_ptr<SX1278::ISX1278Frontend> frontend)
: SX1278Common(bus, cs, dio0, dio1, dio3, clock_divider,
std::move(frontend)),
crc_enabled(false)
{
}
/**
* @brief Setup the device.
......@@ -148,7 +165,7 @@ public:
*
* @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
* @return Size of the data received or -1 on failure
*/
ssize_t receive(uint8_t *pkt, size_t max_len) override;
......@@ -171,32 +188,17 @@ public:
/**
* @brief Get the RSSI in dBm, during last packet receive.
*/
float getLastRxRssi();
float getLastRxRssi() override;
/**
* @brief Get the frequency error index in Hz, during last packet receive.
*/
float getLastRxFei();
/**
* @brief Dump all registers via TRACE.
*/
void debugDumpRegisters();
protected:
// Stuff to work with various front-ends
virtual void enableRxFrontend() override {}
virtual void disableRxFrontend() override {}
virtual void enableTxFrontend() override {}
virtual void disableTxFrontend() override {}
float getLastRxFei() override;
private:
void rateLimitTx();
void enterFskMode();
void imageCalibrate();
SX1278::DioMask getDioMaskFromIrqFlags(IrqFlags flags, Mode mode,
SX1278::DioMapping mapping) override;
void rateLimitTx();
IrqFlags getIrqFlags() override;
void resetIrqFlags(IrqFlags flags) override;
......@@ -207,20 +209,10 @@ 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);
bool crc_enabled;
long long last_tx = 0;
float last_rx_rssi = 0.0f;
PrintLogger logger = Logging::getLogger("sx1278");
PrintLogger logger = Logging::getLogger("sx1278-fsk");
};
} // namespace Boardcore
......@@ -135,7 +135,6 @@ SX1278Lora::Error SX1278Lora::init(const Config &config)
// First probe for the device
if (!checkVersion())
{
TRACE("[sx1278] Wrong chipid\n");
return Error::BAD_VALUE;
}
......@@ -149,22 +148,46 @@ SX1278Lora::Error SX1278Lora::init(const Config &config)
bool SX1278Lora::checkVersion()
{
Lock guard(*this);
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
return spi.readRegister(REG_VERSION) == 0x12;
uint8_t version = spi.readRegister(REG_VERSION);
if (version == 0x12)
{
return true;
}
else
{
LOG_ERR(logger, "Wrong chip id: {}", version);
return false;
}
}
SX1278Lora::Error SX1278Lora::configure(const Config &config)
{
// First cycle the device to bring it into LoRa mode (can only be changed in
// sleep)
setDefaultMode(RegOpMode::MODE_SLEEP, DEFAULT_MAPPING, false, false);
// Make sure the device remains in standby and not in sleep
setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, false, false);
// Check that the configuration is actually valid
bool pa_boost = getFrontend().isOnPaBoost();
int min_power = pa_boost ? 2 : 0;
int max_power = getFrontend().maxInPower();
assert(config.power >= min_power && config.power <= max_power &&
"[sx1278] Configured power invalid for given frontend!");
assert(((config.ocp >= 0 && config.ocp <= 120) ||
(config.ocp >= 130 && config.ocp <= 240)) &&
"[sx1278] Invalid ocp!");
assert(config.freq_rf >= MIN_FREQ_RF && config.freq_rf <= MAX_FREQ_RF &&
"[sx1278] Invalid freq_rf");
// First make sure the device is in lora mode and in standby
enterLoraMode();
// Then make sure the device remains in standby and not in sleep
setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING,
InterruptTrigger::RISING_EDGE, false, false);
// Lock the bus
Lock guard(*this);
LockMode mode_guard(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING);
LockMode mode_guard(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING,
InterruptTrigger::RISING_EDGE);
RegModemConfig1::Bw bw = static_cast<RegModemConfig1::Bw>(config.bandwidth);
RegModemConfig1::Cr cr =
......@@ -172,10 +195,10 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config)
RegModemConfig2::Sf sf =
static_cast<RegModemConfig2::Sf>(config.spreading_factor);
int freq_rf = config.freq_rf;
int ocp = config.ocp;
int power = config.power;
bool pa_boost = config.pa_boost;
int freq_rf = std::max(std::min(config.freq_rf, MAX_FREQ_RF), MIN_FREQ_RF);
int ocp = config.ocp <= 120 ? std::max(std::min(config.ocp, 120), 0)
: std::max(std::min(config.ocp, 240), 130);
int power = std::max(std::min(config.power, max_power), min_power);
bool low_data_rate_optimize = config.low_data_rate_optimize;
......@@ -187,8 +210,10 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config)
ErrataRegistersValues errata_values =
ErrataRegistersValues::calculate(bw, freq_rf);
crc_enabled = config.enable_crc;
{
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
// Setup FIFO sections
spi.writeRegister(REG_FIFO_TX_BASE_ADDR, FIFO_TX_BASE_ADDR);
......@@ -197,10 +222,7 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config)
// Setup frequency
uint32_t freq_rf_raw = errata_values.freq_rf / FSTEP;
spi.writeRegister(REG_FRF_MSB, freq_rf_raw >> 16);
spi.writeRegister(REG_FRF_MID, freq_rf_raw >> 8);
spi.writeRegister(REG_FRF_LSB, freq_rf_raw);
spi.writeRegister24(REG_FRF_MSB, freq_rf_raw);
// Setup reg power amplifier
const int MAX_POWER = 0b111;
......@@ -244,7 +266,7 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config)
spi.writeRegister(REG_MODEM_CONFIG_1,
RegModemConfig1::make(false, cr, bw));
spi.writeRegister(REG_MODEM_CONFIG_2,
RegModemConfig2::make(false, false, sf));
RegModemConfig2::make(crc_enabled, false, sf));
spi.writeRegister(REG_MODEM_CONFIG_3,
RegModemConfig3::make(true, low_data_rate_optimize));
......@@ -277,24 +299,27 @@ ssize_t SX1278Lora::receive(uint8_t *pkt, size_t max_len)
{
Lock guard(*this);
SPITransaction spi(slave);
do
{
// Use continuous because it doesn't go into timeout (and you cannot
// disable it...)
LockMode mode_guard(*this, guard, RegOpMode::MODE_RXCONTINUOUS,
DioMapping(0, 0, 0, 0, 0, 0), false, true);
DioMapping(0, 0, 0, 0, 0, 0),
InterruptTrigger::RISING_EDGE, false, true);
waitForIrq(mode_guard, RegIrqFlags::RX_DONE, true);
} while (checkForIrqAndReset(RegIrqFlags::PAYLOAD_CRC_ERROR));
waitForIrq(mode_guard, RegIrqFlags::RX_DONE, 0, true);
uint8_t len = spi.readRegister(REG_RX_NB_BYTES);
if (len > max_len)
uint8_t len;
{
SPITransaction spi(getSpiSlave());
len = spi.readRegister(REG_RX_NB_BYTES);
}
if (len > max_len ||
(crc_enabled &&
checkForIrqAndReset(RegIrqFlags::PAYLOAD_CRC_ERROR, 0) != 0))
return -1;
// Finally read the contents of the fifo
readFifo(FIFO_RX_BASE_ADDR, pkt, len);
return len;
}
......@@ -305,18 +330,21 @@ bool SX1278Lora::send(uint8_t *pkt, size_t len)
Lock guard(*this);
SPITransaction spi(slave);
{
SPITransaction spi(getSpiSlave());
spi.writeRegister(REG_PAYLOAD_LENGTH, len);
writeFifo(FIFO_TX_BASE_ADDR, pkt, len);
}
{
// Now enter in mode TX to send the packet
LockMode mode_guard(*this, guard, RegOpMode::MODE_TX,
DioMapping(1, 0, 0, 0, 0, 0), true, false);
DioMapping(1, 0, 0, 0, 0, 0),
InterruptTrigger::RISING_EDGE, true, false);
// Wait for the transmission to end
waitForIrq(mode_guard, RegIrqFlags::TX_DONE);
waitForIrq(mode_guard, RegIrqFlags::TX_DONE, 0);
}
return true;
......@@ -327,7 +355,7 @@ float SX1278Lora::getLastRxRssi()
float rssi;
{
Lock guard(*this);
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
rssi =
static_cast<float>(spi.readRegister(REG_PKT_RSSI_VALUE)) - 164.0f;
}
......@@ -343,70 +371,58 @@ float SX1278Lora::getLastRxRssi()
float SX1278Lora::getLastRxSnr()
{
Lock guard(*this);
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
return static_cast<float>(
static_cast<int8_t>(spi.readRegister(REG_PKT_SNR_VALUE))) /
4.0f;
}
void SX1278Lora::enterLoraMode()
{
Lock guard(*this);
SPITransaction spi(getSpiSlave());
// First enter LoRa sleep
spi.writeRegister(REG_OP_MODE,
RegOpMode::make(RegOpMode::MODE_SLEEP, true, false));
miosix::Thread::sleep(1);
// Then transition to standby
spi.writeRegister(REG_OP_MODE,
RegOpMode::make(RegOpMode::MODE_STDBY, true, false));
miosix::Thread::sleep(1);
}
void SX1278Lora::readFifo(uint8_t addr, uint8_t *dst, uint8_t size)
{
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
spi.writeRegister(REG_FIFO_ADDR_PTR, addr);
spi.readRegisters(REG_FIFO, dst, size);
}
void SX1278Lora::writeFifo(uint8_t addr, uint8_t *src, uint8_t size)
{
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
spi.writeRegister(REG_FIFO_ADDR_PTR, addr);
spi.writeRegisters(REG_FIFO, src, size);
}
SX1278::DioMask SX1278Lora::getDioMaskFromIrqFlags(IrqFlags flags, Mode _mode,
SX1278::DioMapping mapping)
{
// In LoRa the mode doesn't matter for IRQs
(void)_mode;
DioMask dio_mask;
if (DIO_MAPPINGS[0][mapping.getMapping(Dio::DIO0)] & flags)
dio_mask.set(Dio::DIO0);
if (DIO_MAPPINGS[1][mapping.getMapping(Dio::DIO1)] & flags)
dio_mask.set(Dio::DIO1);
if (DIO_MAPPINGS[2][mapping.getMapping(Dio::DIO2)] & flags)
dio_mask.set(Dio::DIO2);
if (DIO_MAPPINGS[3][mapping.getMapping(Dio::DIO3)] & flags)
dio_mask.set(Dio::DIO3);
if (DIO_MAPPINGS[4][mapping.getMapping(Dio::DIO4)] & flags)
dio_mask.set(Dio::DIO4);
if (DIO_MAPPINGS[5][mapping.getMapping(Dio::DIO5)] & flags)
dio_mask.set(Dio::DIO5);
return dio_mask;
}
ISX1278::IrqFlags SX1278Lora::getIrqFlags()
{
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
return spi.readRegister(REG_IRQ_FLAGS);
}
void SX1278Lora::resetIrqFlags(IrqFlags flags)
{
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
// Register is write clear
spi.writeRegister(REG_IRQ_FLAGS, flags);
}
void SX1278Lora::setMode(ISX1278::Mode mode)
{
SPITransaction spi(slave);
SPITransaction spi(getSpiSlave());
spi.writeRegister(
REG_OP_MODE,
......@@ -415,9 +431,8 @@ void SX1278Lora::setMode(ISX1278::Mode mode)
void SX1278Lora::setMapping(SX1278::DioMapping mapping)
{
SPITransaction spi(slave);
spi.writeRegister(REG_DIO_MAPPING_1, mapping.raw >> 8);
spi.writeRegister(REG_DIO_MAPPING_2, mapping.raw);
SPITransaction spi(getSpiSlave());
spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw);
}
} // namespace Boardcore
......@@ -22,6 +22,8 @@
#pragma once
#include <diagnostic/PrintLogger.h>
#include "SX1278Common.h"
#include "SX1278LoraTimings.h"
......@@ -102,10 +104,10 @@ 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).
bool pa_boost = true; //< Enable output on PA_BOOST.
bool enable_crc = true; //< Enable hardware CRC calculation/checking
/**
* @brief Calculates effective and usable bitrate.
......@@ -133,7 +135,18 @@ public:
IRQ_TIMEOUT, //< Timeout on IRQ register.
};
explicit SX1278Lora(SPISlave slave) : SX1278Common(slave) {}
/**
* @brief Construct a new SX1278
*/
explicit SX1278Lora(SPIBus &bus, miosix::GpioPin cs, miosix::GpioPin dio0,
miosix::GpioPin dio1, miosix::GpioPin dio3,
SPI::ClockDivider clock_divider,
std::unique_ptr<SX1278::ISX1278Frontend> frontend)
: SX1278Common(bus, cs, dio0, dio1, dio3, clock_divider,
std::move(frontend)),
crc_enabled(false)
{
}
/**
* @brief Setup the device.
......@@ -173,34 +186,27 @@ public:
/**
* @brief Get the RSSI in dBm, during last packet receive.
*/
float getLastRxRssi();
float getLastRxRssi() override;
/**
* @brief Get the RSSI in dBm, during last packet receive.
*/
float getLastRxSnr();
protected:
// Stuff to work with various front-ends
virtual void enableRxFrontend() override {}
virtual void disableRxFrontend() override {}
virtual void enableTxFrontend() override {}
virtual void disableTxFrontend() override {}
float getLastRxSnr() override;
private:
void enterLoraMode();
void readFifo(uint8_t addr, uint8_t *dst, uint8_t size);
void writeFifo(uint8_t addr, uint8_t *src, uint8_t size);
SX1278::DioMask getDioMaskFromIrqFlags(IrqFlags flags, Mode mode,
SX1278::DioMapping mapping) override;
IrqFlags getIrqFlags() override;
void resetIrqFlags(IrqFlags flags) override;
void setMode(Mode mode) override;
void setMapping(SX1278::DioMapping mapping) override;
void setFreqRF(int freq_rf);
bool crc_enabled;
PrintLogger logger = Logging::getLogger("sx1278-lora");
};
} // namespace Boardcore
......@@ -44,7 +44,9 @@ public:
ssize_t receive(uint8_t* packet, size_t packetLength)
{
return usart.readBlocking(packet, packetLength);
size_t bytesRead = 0;
bool result = usart.readBlocking(packet, packetLength, bytesRead);
return result ? bytesRead : 0;
}
private:
......
......@@ -64,7 +64,7 @@ bool Xbee::send(uint8_t* pkt, size_t packetLength)
MAX_PACKET_PAYLOAD_LENGTH);
return false;
}
long long startTick = miosix::getTick();
long long startTick = Kernel::getOldTick();
TXRequestFrame txReq;
uint8_t txFrameId = buildTXRequestFrame(txReq, pkt, packetLength);
......@@ -75,7 +75,7 @@ bool Xbee::send(uint8_t* pkt, size_t packetLength)
writeFrame(txReq);
// Wait for a TX Status frame
long long timeoutTick = miosix::getTick() + txTimeout;
long long timeoutTick = Kernel::getOldTick() + txTimeout;
while (waitForFrame(FTYPE_TX_STATUS, FRAME_POLL_INTERVAL, timeoutTick))
{
......@@ -106,7 +106,7 @@ bool Xbee::send(uint8_t* pkt, size_t packetLength)
++status.txTimeoutCount;
LOG_ERR(logger, "TX_STATUS timeout");
}
timeToSendStats.add(miosix::getTick() - startTick);
timeToSendStats.add(Kernel::getOldTick() - startTick);
StackLogger::getInstance().updateStack(THID_XBEE);
......@@ -160,7 +160,7 @@ ssize_t Xbee::receive(uint8_t* buf, size_t bufMaxSize)
XbeeStatus Xbee::getStatus()
{
status.timestamp = miosix::getTick();
status.timestamp = Kernel::getOldTick();
status.timeToSendStats = timeToSendStats.getStats();
return status;
}
......@@ -178,7 +178,7 @@ void Xbee::reset()
// When the xbee is ready, we should assert SSEL to tell it to use
// SPI, and it should provide us with a modem status frame
long long timeout = miosix::getTick() + 1000;
long long timeout = Kernel::getOldTick() + 1000;
do
{
// Assert SSEL on every iteration as we don't exactly know when the
......@@ -200,7 +200,7 @@ void Xbee::reset()
break;
}
miosix::Thread::sleep(5);
} while (miosix::getTick() < timeout);
} while (Kernel::getOldTick() < timeout);
}
void Xbee::wakeReceiver(bool forceReturn)
......@@ -293,7 +293,7 @@ bool Xbee::readRXFrame()
void Xbee::writeFrame(APIFrame& frame)
{
frame.timestamp = miosix::getTick(); // Only for logging purposes
frame.timestamp = Kernel::getOldTick(); // Only for logging purposes
// Serialize the frame
uint8_t txBuf[MAX_API_FRAME_SIZE];
......@@ -337,7 +337,7 @@ bool Xbee::waitForFrame(uint8_t frameType, unsigned int pollInterval,
{
miosix::Thread::sleep(pollInterval);
}
} while (miosix::getTick() < timeoutTick);
} while (Kernel::getOldTick() < timeoutTick);
return false;
}
......@@ -380,7 +380,7 @@ bool Xbee::sendATCommand(const char* cmd, ATCommandResponseFrame* response,
bool success = false;
long long timeoutTick = miosix::getTick() + timeout;
long long timeoutTick = Kernel::getOldTick() + timeout;
while (waitForFrame(FTYPE_AT_COMMAND_RESPONSE, FRAME_POLL_INTERVAL,
timeoutTick))
......@@ -435,7 +435,7 @@ uint8_t Xbee::sendATCommandInternal(uint8_t txFrameId, const char* cmd,
void Xbee::handleFrame(APIFrame& frame)
{
// Set the timestamp to the frame
frame.timestamp = miosix::getTick();
frame.timestamp = Kernel::getOldTick();
switch (frame.frameType)
{
......
......@@ -23,23 +23,18 @@
#include "TaskScheduler.h"
#include <diagnostic/SkywardStack.h>
#include <utils/TimeUtils.h>
#include <algorithm>
#include <mutex>
using namespace std;
using namespace std::chrono;
using namespace miosix;
namespace Boardcore
{
namespace Constants
{
static constexpr unsigned int TICKS_PER_MS =
miosix::TICK_FREQ / 1000; // Number of ticks in a millisecond
static constexpr unsigned int MS_PER_TICK =
1000 / miosix::TICK_FREQ; // Number of milliseconds in a tick
} // namespace Constants
TaskScheduler::EventQueue TaskScheduler::makeAgenda()
{
std::vector<Event> agendaStorage{};
......@@ -59,52 +54,47 @@ TaskScheduler::TaskScheduler(miosix::Priority priority)
tasks.emplace_back();
}
size_t TaskScheduler::addTask(function_t function, uint32_t period,
Policy policy, int64_t startTick)
size_t TaskScheduler::addTask(function_t function, nanoseconds period,
Policy policy, time_point<steady_clock> startTime)
{
// In the case of early returns, using RAII mutex wrappers to unlock the
// mutex would cause it to be locked and unlocked one more time before
// returning, because of the destructor being called on the Unlock object
// first and then on the Lock object. To avoid this, we don't use RAII
// wrappers and manually lock and unlock the mutex instead.
mutex.lock();
std::unique_lock<miosix::FastMutex> lock{mutex};
if (tasks.size() >= MAX_TASKS)
{
// Unlock the mutex to release the scheduler resources before logging
mutex.unlock();
lock.unlock();
LOG_ERR(logger, "Full task scheduler");
return 0;
}
if (policy == Policy::ONE_SHOT)
{
startTick += period;
startTime += period;
}
// Insert a new task with the given parameters
tasks.emplace_back(function, period, policy, startTick);
tasks.emplace_back(function, period.count(), policy,
startTime.time_since_epoch().count());
size_t id = tasks.size() - 1;
// Only add the task to the agenda if the scheduler is running
// Otherwise, the agenda will be populated when the scheduler is started
if (isRunning())
{
agenda.emplace(id, startTick);
agenda.emplace(id, startTime.time_since_epoch().count());
}
condvar.broadcast(); // Signals the run thread
mutex.unlock();
return id;
}
void TaskScheduler::enableTask(size_t id)
{
mutex.lock();
std::unique_lock<miosix::FastMutex> lock{mutex};
if (id > tasks.size() - 1)
{
mutex.unlock();
lock.unlock();
LOG_ERR(logger, "Tried to enable an out-of-range task, id = {}", id);
return;
}
......@@ -116,29 +106,30 @@ void TaskScheduler::enableTask(size_t id)
// exception
if (task.empty())
{
mutex.unlock();
lock.unlock();
LOG_WARN(logger, "Tried to enable an empty task, id = {}", id);
return;
}
task.enabled = true;
agenda.emplace(id, getTick() + task.period * Constants::TICKS_PER_MS);
mutex.unlock();
agenda.emplace(id, miosix::getTime() + task.period);
}
void TaskScheduler::disableTask(size_t id)
{
mutex.lock();
std::unique_lock<miosix::FastMutex> lock{mutex};
if (id > tasks.size() - 1)
{
mutex.unlock();
lock.unlock();
LOG_ERR(logger, "Tried to disable an out-of-range task, id = {}", id);
return;
}
tasks[id].enabled = false;
mutex.unlock();
Task& task = tasks[id];
task.enabled = false;
// Reset the last call time to avoid incorrect period statistics
task.lastCall = -1;
}
bool TaskScheduler::start()
......@@ -186,21 +177,24 @@ vector<TaskStatsResult> TaskScheduler::getTaskStats()
void TaskScheduler::populateAgenda()
{
int64_t currentTick = getTick();
int64_t currentTime = miosix::getTime();
for (size_t id = 1; id < tasks.size(); id++)
{
Task& task = tasks[id];
int64_t startTime = task.startTime;
int64_t nextTick = task.startTick;
// Normalize the tasks start time if they precede the current tick
if (nextTick < currentTick)
// Shift the task's start time if it precedes the current time
// to avoid clumping all tasks at the beginning (see issue #91)
if (startTime < currentTime)
{
nextTick +=
((currentTick - nextTick) / task.period + 1) * task.period;
int64_t timeSinceStart = currentTime - startTime;
int64_t periodsMissed = timeSinceStart / task.period;
int64_t periodsToSkip = periodsMissed + 1;
startTime += periodsToSkip * task.period;
}
agenda.emplace(id, nextTick);
agenda.emplace(id, startTime);
}
}
......@@ -221,19 +215,12 @@ void TaskScheduler::run()
return;
}
int64_t startTick = getTick();
int64_t startTime = miosix::getTime();
Event nextEvent = agenda.top();
Task& nextTask = tasks[nextEvent.taskId];
// If the task has the SKIP policy and its execution was missed, we need
// to move it forward to match the period
if (nextEvent.nextTick < startTick && nextTask.policy == Policy::SKIP)
{
agenda.pop();
enqueue(nextEvent, startTick);
}
else if (nextEvent.nextTick <= startTick)
if (nextEvent.nextTime <= startTime)
{
Task& nextTask = tasks[nextEvent.taskId];
agenda.pop();
// Execute the task function
......@@ -254,42 +241,42 @@ void TaskScheduler::run()
}
// Enqueue only on a valid task
updateStats(nextEvent, startTick, getTick());
enqueue(nextEvent, startTick);
updateStats(nextEvent, startTime, miosix::getTime());
enqueue(nextEvent, startTime);
}
}
else
{
Unlock<FastMutex> unlock(lock);
Thread::sleepUntil(nextEvent.nextTick);
Thread::nanoSleepUntil(nextEvent.nextTime);
}
}
}
void TaskScheduler::updateStats(const Event& event, int64_t startTick,
int64_t endTick)
void TaskScheduler::updateStats(const Event& event, int64_t startTime,
int64_t endTime)
{
Task& task = tasks[event.taskId];
// Activation stats
float activationError = startTick - event.nextTick;
task.activationStats.add(activationError * Constants::MS_PER_TICK);
float activationTime = startTime - event.nextTime;
task.activationStats.add(activationTime / Constants::NS_IN_MS);
// Period stats
int64_t lastCall = task.lastCall;
if (lastCall >= 0)
task.periodStats.add((startTick - lastCall) * Constants::MS_PER_TICK);
// Update the last call tick to the current start tick for the next
{
float periodTime = startTime - lastCall;
task.periodStats.add(periodTime / Constants::NS_IN_MS);
}
// Update the last call time to the current start time for the next
// iteration
task.lastCall = startTick;
task.lastCall = startTime;
// Workload stats
task.workloadStats.add(endTick - startTick);
float workloadTime = endTime - startTime;
task.workloadStats.add(workloadTime / Constants::NS_IN_MS);
}
void TaskScheduler::enqueue(Event event, int64_t startTick)
void TaskScheduler::enqueue(Event event, int64_t startTime)
{
Task& task = tasks[event.taskId];
switch (task.policy)
......@@ -300,21 +287,26 @@ void TaskScheduler::enqueue(Event event, int64_t startTick)
task.enabled = false;
return;
case Policy::SKIP:
{
// Compute the number of missed periods since the last execution
int64_t timeSinceLastExec = startTime - event.nextTime;
int64_t periodsMissed = timeSinceLastExec / task.period;
// Schedule the task executon to the next aligned period, by
// skipping over the missed ones
// E.g. 3 periods have passed since last execution, the next viable
// schedule time is after 4 periods
int64_t periodsToSkip = periodsMissed + 1;
// Update the task to run at the next viable timeslot, while still
// being aligned to the original one
event.nextTime += periodsToSkip * task.period;
// Updated the missed events count
task.missedEvents += (startTick - event.nextTick) / task.period;
// Compute the number of periods between the tick the event should
// have been run and the tick it actually run. Than adds 1 and
// multiply the period to get the next execution tick still aligned
// to the original one.
// E.g. If a task has to run once every 2 ticks and start at tick 0
// but for whatever reason the first execution is at tick 3, then
// the next execution will be at tick 4.
event.nextTick +=
((startTick - event.nextTick) / task.period + 1) * task.period;
task.missedEvents += static_cast<uint32_t>(periodsMissed);
break;
}
case Policy::RECOVER:
event.nextTick += task.period * Constants::TICKS_PER_MS;
event.nextTime += task.period;
break;
}
......@@ -324,15 +316,15 @@ void TaskScheduler::enqueue(Event event, int64_t startTick)
}
TaskScheduler::Task::Task()
: function(nullptr), period(0), startTick(0), enabled(false),
: function(nullptr), period(0), startTime(0), enabled(false),
policy(Policy::SKIP), lastCall(-1), activationStats(), periodStats(),
workloadStats(), missedEvents(0), failedEvents(0)
{
}
TaskScheduler::Task::Task(function_t function, uint32_t period, Policy policy,
int64_t startTick)
: function(function), period(period), startTick(startTick), enabled(true),
TaskScheduler::Task::Task(function_t function, int64_t period, Policy policy,
int64_t startTime)
: function(function), period(period), startTime(startTime), enabled(true),
policy(policy), lastCall(-1), activationStats(), periodStats(),
workloadStats(), missedEvents(0), failedEvents(0)
{
......