Skip to content

Commit

Permalink
[SPI] Fix SPI nanosecond timing
Browse files Browse the repository at this point in the history
  • Loading branch information
digitalentity committed Nov 7, 2020
1 parent e72e702 commit 4b31a2f
Show file tree
Hide file tree
Showing 5 changed files with 26 additions and 40 deletions.
30 changes: 12 additions & 18 deletions src/main/drivers/bus_busdev_spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -78,15 +78,13 @@ bool spiBusTransfer(const busDevice_t * dev, uint8_t * rxBuf, const uint8_t * tx
SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
IOLo(dev->busdev.spi.csnPin);
spiChipSelectSetupDelay();
spiBusSelectDevice(dev);
}

spiTransfer(instance, rxBuf, txBuf, length);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
spiChipSelectHoldTime();
IOHi(dev->busdev.spi.csnPin);
spiBusDeselectDevice(dev);
}

return true;
Expand All @@ -97,17 +95,15 @@ bool spiBusTransferMultiple(const busDevice_t * dev, busTransferDescriptor_t * d
SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
IOLo(dev->busdev.spi.csnPin);
spiChipSelectSetupDelay();
spiBusSelectDevice(dev);
}

for (int n = 0; n < count; n++) {
spiTransfer(instance, dsc[n].rxBuf, dsc[n].txBuf, dsc[n].length);
}

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
spiChipSelectHoldTime();
IOHi(dev->busdev.spi.csnPin);
spiBusDeselectDevice(dev);
}

return true;
Expand All @@ -118,16 +114,14 @@ bool spiBusWriteRegister(const busDevice_t * dev, uint8_t reg, uint8_t data)
SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
IOLo(dev->busdev.spi.csnPin);
delayMicroseconds(1);
spiBusSelectDevice(dev);
}

spiTransferByte(instance, reg);
spiTransferByte(instance, data);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
delayMicroseconds(1);
IOHi(dev->busdev.spi.csnPin);
spiBusDeselectDevice(dev);
}

return true;
Expand All @@ -138,14 +132,14 @@ bool spiBusWriteBuffer(const busDevice_t * dev, uint8_t reg, const uint8_t * dat
SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
IOLo(dev->busdev.spi.csnPin);
spiBusSelectDevice(dev);
}

spiTransferByte(instance, reg);
spiTransfer(instance, NULL, data, length);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
IOHi(dev->busdev.spi.csnPin);
spiBusDeselectDevice(dev);
}

return true;
Expand All @@ -156,14 +150,14 @@ bool spiBusReadBuffer(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint
SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
IOLo(dev->busdev.spi.csnPin);
spiBusSelectDevice(dev);
}

spiTransferByte(instance, reg);
spiTransfer(instance, data, NULL, length);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
IOHi(dev->busdev.spi.csnPin);
spiBusDeselectDevice(dev);
}

return true;
Expand All @@ -174,14 +168,14 @@ bool spiBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data)
SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
IOLo(dev->busdev.spi.csnPin);
spiBusSelectDevice(dev);
}

spiTransferByte(instance, reg);
spiTransfer(instance, data, NULL, 1);

if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
IOHi(dev->busdev.spi.csnPin);
spiBusDeselectDevice(dev);
}

return true;
Expand Down
2 changes: 2 additions & 0 deletions src/main/drivers/max7456.c
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@ FILE_COMPILE_FOR_SPEED
#define BOUNDS_CHECK_FAILED() do {} while(0)
#endif

#include "build/debug.h"

#include "common/bitarray.h"
#include "common/printf.h"
#include "common/utils.h"
Expand Down
16 changes: 9 additions & 7 deletions src/main/drivers/system.c
Original file line number Diff line number Diff line change
Expand Up @@ -29,35 +29,37 @@
#include "drivers/system.h"
#include "drivers/time.h"

#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
// See "RM CoreSight Architecture Specification"
// B2.3.10 "LSR and LAR, Software Lock Status Register and Software Lock Access Register"
// "E1.2.11 LAR, Lock Access Register"
#define DWT_LAR_UNLOCK_VALUE 0xC5ACCE55
#endif

// cached value of RCC->CSR
uint32_t cachedRccCsrValue;

void cycleCounterInit(void)
{
extern uint32_t usTicks; // From drivers/time.h

#if defined(USE_HAL_DRIVER)
// We assume that SystemCoreClock is already set to a correct value by init code
usTicks = SystemCoreClock / 1000000;
nsTicks = SystemCoreClock / 1000;
#else
RCC_ClocksTypeDef clocks;
RCC_GetClocksFreq(&clocks);
usTicks = clocks.SYSCLK_Frequency / 1000000;
nsTicks = clocks.SYSCLK_Frequency / 1000;
#endif

// Enable DWT for precision time measurement
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;

#if defined(DWT_LAR_UNLOCK_VALUE)
#if defined(STM32F7) || defined(STM32H7)
DWT->LAR = DWT_LAR_UNLOCK_VALUE;
#elif defined(STM32F3) || defined(STM32F4)
// Note: DWT_Type does not contain LAR member.
#define DWT_LAR
__O uint32_t *DWTLAR = (uint32_t *)(DWT_BASE + 0x0FB0);
volatile uint32_t *DWTLAR = (uint32_t *)(DWT_BASE + 0x0FB0);
*(DWTLAR) = DWT_LAR_UNLOCK_VALUE;
#endif
#endif

DWT->CYCCNT = 0;
Expand Down
15 changes: 2 additions & 13 deletions src/main/drivers/time.c
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@
// cycles per microsecond, this is deliberately uint32_t to avoid type conversions
// This is not static so system.c can set it up for us.
uint32_t usTicks = 0;
uint32_t nsTicks = 0;

// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
STATIC_UNIT_TESTED volatile timeMs_t sysTickUptime = 0;
Expand Down Expand Up @@ -71,25 +70,15 @@ uint32_t ticks(void)
#ifdef UNIT_TEST
return 0;
#else
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
return DWT->CYCCNT;
#endif
}

timeDelta_t ticks_diff_us(uint32_t begin, uint32_t end)
{
return (end - begin) / usTicks;
}

timeDelta_t ticks_diff_ns(uint32_t begin, uint32_t end)
{
return (end - begin) / nsTicks;
}

void delayNanos(timeDelta_t ns)
{
const uint32_t startTicks = ticks();
while (ticks_diff_ns(startTicks, ticks()) < ns);
const uint32_t ticksToWait = (ns * usTicks) / 1000;
while (ticks() - startTicks <= ticksToWait);
}

// Return system uptime in microseconds
Expand Down
3 changes: 1 addition & 2 deletions src/main/drivers/time.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,11 @@ extern uint32_t usTicks;
extern uint32_t nsTicks;

void delayMicroseconds(timeUs_t us);
void delayNanos(timeDelta_t ns);
void delay(timeMs_t ms);

timeUs_t micros(void);
timeUs_t microsISR(void);
timeMs_t millis(void);

uint32_t ticks(void);
timeDelta_t ticks_diff_us(uint32_t begin, uint32_t end);
void delayNanos(timeDelta_t ns);

0 comments on commit 4b31a2f

Please sign in to comment.