diff options
author | David Crocker <dcrocker@eschertech.com> | 2021-04-02 13:46:24 +0300 |
---|---|---|
committer | David Crocker <dcrocker@eschertech.com> | 2021-04-02 13:46:24 +0300 |
commit | 52afd5e7f34200a7ae9d3d9b56e95acc5300c6d0 (patch) | |
tree | d57d39053510c8ea26e23b4e3bc1c5cabbf70141 /src | |
parent | a38e510ce9bd34bce7fab6923297cb11b0e161a7 (diff) |
Use new interrupt enable/disable functions in CoreN2G
Diffstat (limited to 'src')
-rw-r--r-- | src/Fans/LedStripDriver.cpp | 4 | ||||
-rw-r--r-- | src/FilamentMonitors/FilamentMonitor.cpp | 6 | ||||
-rw-r--r-- | src/FilamentMonitors/PulsedFilamentMonitor.cpp | 4 | ||||
-rw-r--r-- | src/Hardware/ExceptionHandlers.cpp | 2 | ||||
-rw-r--r-- | src/InputMonitors/InputMonitor.cpp | 4 | ||||
-rw-r--r-- | src/Libraries/sd_mmc/sd_mmc_spi.h | 4 | ||||
-rw-r--r-- | src/Movement/DDARing.cpp | 22 | ||||
-rw-r--r-- | src/Movement/StepTimer.cpp | 4 | ||||
-rw-r--r-- | src/Movement/StepperDrivers/TMC22xx.cpp | 4 | ||||
-rw-r--r-- | src/Movement/StepperDrivers/TMC2660.cpp | 12 | ||||
-rw-r--r-- | src/Platform/Platform.cpp | 22 | ||||
-rw-r--r-- | src/Platform/Platform.h | 4 | ||||
-rw-r--r-- | src/Platform/RepRap.cpp | 4 | ||||
-rw-r--r-- | src/Storage/FileStore.cpp | 16 |
14 files changed, 59 insertions, 53 deletions
diff --git a/src/Fans/LedStripDriver.cpp b/src/Fans/LedStripDriver.cpp index 193bd2c9..ac1aa87b 100644 --- a/src/Fans/LedStripDriver.cpp +++ b/src/Fans/LedStripDriver.cpp @@ -371,7 +371,7 @@ namespace LedStripDriver { const uint8_t *q = chunkBuffer; uint32_t nextDelay = T0L; - cpu_irq_disable(); + IrqDisable(); uint32_t lastTransitionTime = SysTick->VAL & 0x00FFFFFF; while (q < p) { @@ -397,7 +397,7 @@ namespace LedStripDriver c <<= 1; } } - cpu_irq_enable(); + IrqEnable(); numAlreadyInBuffer = 0; whenDmaFinished = StepTimer::GetTimerTicks(); } diff --git a/src/FilamentMonitors/FilamentMonitor.cpp b/src/FilamentMonitors/FilamentMonitor.cpp index 11835933..dd39bbcb 100644 --- a/src/FilamentMonitors/FilamentMonitor.cpp +++ b/src/FilamentMonitors/FilamentMonitor.cpp @@ -261,19 +261,19 @@ bool FilamentMonitor::IsValid() const noexcept bool fromIsr; int32_t extruderStepsCommanded; uint32_t locIsrMillis; - cpu_irq_disable(); + IrqDisable(); if (fs.haveIsrStepsCommanded) { extruderStepsCommanded = fs.isrExtruderStepsCommanded; isPrinting = fs.isrWasPrinting; locIsrMillis = fs.lastIsrMillis; fs.haveIsrStepsCommanded = false; - cpu_irq_enable(); + IrqEnable(); fromIsr = true; } else { - cpu_irq_enable(); + IrqEnable(); extruderStepsCommanded = reprap.GetMove().GetAccumulatedExtrusion(extruder, isPrinting); // get and clear the net extrusion commanded fromIsr = false; locIsrMillis = 0; diff --git a/src/FilamentMonitors/PulsedFilamentMonitor.cpp b/src/FilamentMonitors/PulsedFilamentMonitor.cpp index 3c865593..f7e2962b 100644 --- a/src/FilamentMonitors/PulsedFilamentMonitor.cpp +++ b/src/FilamentMonitors/PulsedFilamentMonitor.cpp @@ -187,10 +187,10 @@ bool PulsedFilamentMonitor::Interrupt() noexcept // Call the following regularly to keep the status up to date void PulsedFilamentMonitor::Poll() noexcept { - cpu_irq_disable(); + IrqDisable(); const uint32_t locSensorVal = sensorValue; sensorValue = 0; - cpu_irq_enable(); + IrqEnable(); movementMeasuredSinceLastSync += (float)locSensorVal; if (haveInterruptData) // if we have a synchronised value for the amount of extrusion commanded diff --git a/src/Hardware/ExceptionHandlers.cpp b/src/Hardware/ExceptionHandlers.cpp index 24a25bba..7253f5cf 100644 --- a/src/Hardware/ExceptionHandlers.cpp +++ b/src/Hardware/ExceptionHandlers.cpp @@ -17,7 +17,7 @@ // Perform a software reset. 'stk' points to the exception stack (r0 r1 r2 r3 r12 lr pc xPSR) if the cause is an exception, otherwise it is nullptr. [[noreturn]] void SoftwareReset(SoftwareResetReason initialReason, const uint32_t *stk) noexcept { - cpu_irq_disable(); // disable interrupts before we call any flash functions. We don't enable them again. + IrqDisable(); // disable interrupts before we call any flash functions. We don't enable them again. WatchdogReset(); // kick the watchdog #if SAME70 || SAM4E diff --git a/src/InputMonitors/InputMonitor.cpp b/src/InputMonitors/InputMonitor.cpp index 45e6a9a3..5f797606 100644 --- a/src/InputMonitors/InputMonitor.cpp +++ b/src/InputMonitors/InputMonitor.cpp @@ -26,10 +26,10 @@ bool InputMonitor::Activate(bool useInterrupt) noexcept if (threshold == 0) { // Digital input - const irqflags_t flags = cpu_irq_save(); + const irqflags_t flags = IrqSave(); ok = !useInterrupt || port.AttachInterrupt(CommonDigitalPortInterrupt, InterruptMode::change, CallbackParameter(this)); state = port.ReadDigital(); - cpu_irq_restore(flags); + IrqRestore(flags); } else { diff --git a/src/Libraries/sd_mmc/sd_mmc_spi.h b/src/Libraries/sd_mmc/sd_mmc_spi.h index b1b70f10..164bc625 100644 --- a/src/Libraries/sd_mmc/sd_mmc_spi.h +++ b/src/Libraries/sd_mmc/sd_mmc_spi.h @@ -50,6 +50,10 @@ #include <Core.h> #include "sd_mmc_protocol.h" +#ifndef UNUSED +# define UNUSED(_x) (void)(_x) +#endif + #ifdef __cplusplus extern "C" { #endif diff --git a/src/Movement/DDARing.cpp b/src/Movement/DDARing.cpp index 24c76c7f..df0b957e 100644 --- a/src/Movement/DDARing.cpp +++ b/src/Movement/DDARing.cpp @@ -596,13 +596,13 @@ bool DDARing::LiveCoordinates(float m[MaxAxesPlusExtruders]) noexcept // The live coordinates and live endpoints are modified by the ISR, so be careful to get a self-consistent set of them const size_t numVisibleAxes = reprap.GetGCodes().GetVisibleAxes(); // do this before we disable interrupts const size_t numTotalAxes = reprap.GetGCodes().GetTotalAxes(); // do this before we disable interrupts - cpu_irq_disable(); + IrqDisable(); if (liveCoordinatesValid) { // All coordinates are valid, so copy them across memcpyf(m, const_cast<const float *>(liveCoordinates), MaxAxesPlusExtruders); liveCoordinatesChanged = false; - cpu_irq_enable(); + IrqEnable(); } else { @@ -610,19 +610,19 @@ bool DDARing::LiveCoordinates(float m[MaxAxesPlusExtruders]) noexcept memcpyf(m + numTotalAxes, const_cast<const float *>(liveCoordinates + numTotalAxes), MaxAxesPlusExtruders - numTotalAxes); int32_t tempEndPoints[MaxAxes]; memcpyi32(tempEndPoints, const_cast<const int32_t*>(liveEndPoints), ARRAY_SIZE(tempEndPoints)); - cpu_irq_enable(); + IrqEnable(); reprap.GetMove().MotorStepsToCartesian(tempEndPoints, numVisibleAxes, numTotalAxes, m); // this is slow, so do it with interrupts enabled // If the ISR has not updated the endpoints, store the live coordinates back so that we don't need to do it again - cpu_irq_disable(); + IrqDisable(); if (memcmp(tempEndPoints, const_cast<const int32_t*>(liveEndPoints), sizeof(tempEndPoints)) == 0) { memcpyf(const_cast<float *>(liveCoordinates), m, numVisibleAxes); liveCoordinatesValid = true; liveCoordinatesChanged = false; } - cpu_irq_enable(); + IrqEnable(); } return true; } @@ -643,12 +643,12 @@ void DDARing::SetLiveCoordinates(const float coords[MaxAxesPlusExtruders]) noexc void DDARing::ResetExtruderPositions() noexcept { - cpu_irq_disable(); + IrqDisable(); for (size_t eDrive = reprap.GetGCodes().GetTotalAxes(); eDrive < MaxAxesPlusExtruders; eDrive++) { liveCoordinates[eDrive] = 0.0; } - cpu_irq_enable(); + IrqEnable(); liveCoordinatesChanged = true; } @@ -708,7 +708,7 @@ bool DDARing::PauseMoves(RestorePoint& rp) noexcept const DDA * const savedDdaRingAddPointer = addPointer; bool pauseOkHere; - cpu_irq_disable(); + IrqDisable(); DDA *dda = currentDda; if (dda == nullptr) { @@ -733,7 +733,7 @@ bool DDARing::PauseMoves(RestorePoint& rp) noexcept dda = dda->GetNext(); } - cpu_irq_enable(); + IrqEnable(); // We may be going to skip some moves. Get the end coordinate of the previous move. DDA * const prevDda = addPointer->GetPrevious(); @@ -785,7 +785,7 @@ bool DDARing::LowPowerOrStallPause(RestorePoint& rp) noexcept const DDA * const savedDdaRingAddPointer = addPointer; bool abortedMove = false; - cpu_irq_disable(); + IrqDisable(); DDA *dda = currentDda; if (dda != nullptr && dda->GetFilePosition() != noFilePosition) { @@ -820,7 +820,7 @@ bool DDARing::LowPowerOrStallPause(RestorePoint& rp) noexcept } } - cpu_irq_enable(); + IrqEnable(); if (dda == savedDdaRingAddPointer) { diff --git a/src/Movement/StepTimer.cpp b/src/Movement/StepTimer.cpp index d72dbf3b..891ab9c6 100644 --- a/src/Movement/StepTimer.cpp +++ b/src/Movement/StepTimer.cpp @@ -125,7 +125,7 @@ void StepTimer::Init() noexcept STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_RA = 0x0001; STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_RC = 0x0002; - cpu_irq_disable(); + IrqDisable(); tc_start(STEP_TC, STEP_TC_CHAN_UPPER); tc_start(STEP_TC, STEP_TC_CHAN); @@ -134,7 +134,7 @@ void StepTimer::Init() noexcept STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_RA = 0xFFFF; STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_RC = 0; - cpu_irq_enable(); + IrqEnable(); # else // Use a single 32-bit timer. CLOCK4 is MCLK/128. diff --git a/src/Movement/StepperDrivers/TMC22xx.cpp b/src/Movement/StepperDrivers/TMC22xx.cpp index e94a19c0..585ed599 100644 --- a/src/Movement/StepperDrivers/TMC22xx.cpp +++ b/src/Movement/StepperDrivers/TMC22xx.cpp @@ -1267,10 +1267,10 @@ uint32_t TmcDriverState::ReadAccumulatedStatus(uint32_t bitsToKeep) noexcept { const uint32_t mask = (enabled) ? 0xFFFFFFFF : ~(TMC_RR_OLA | TMC_RR_OLB); bitsToKeep &= mask; - const irqflags_t flags = cpu_irq_save(); + const irqflags_t flags = IrqSave(); uint32_t status = accumulatedReadRegisters[ReadDrvStat]; accumulatedReadRegisters[ReadDrvStat] = (status & bitsToKeep) | readRegisters[ReadDrvStat]; // so that the next call to ReadAccumulatedStatus isn't missing some bits - cpu_irq_restore(flags); + IrqRestore(flags); status &= (TMC_RR_OT | TMC_RR_OTPW | TMC_RR_S2G | TMC_RR_OLA | TMC_RR_OLB | TMC_RR_STST | TMC_RR_TEMPBITS) & mask; #if HAS_STALL_DETECT if (IoPort::ReadPin(diagPin)) diff --git a/src/Movement/StepperDrivers/TMC2660.cpp b/src/Movement/StepperDrivers/TMC2660.cpp index 4c9332c3..c7c7de99 100644 --- a/src/Movement/StepperDrivers/TMC2660.cpp +++ b/src/Movement/StepperDrivers/TMC2660.cpp @@ -602,7 +602,7 @@ void TmcDriverState::Enable(bool en) noexcept enabled = en; UpdateChopConfRegister(); - const irqflags_t flags = cpu_irq_save(); + const irqflags_t flags = IrqSave(); mstepPosition = 0xFFFFFFFF; // microstep position is or is about to become invalid if (en) { @@ -618,7 +618,7 @@ void TmcDriverState::Enable(bool en) noexcept } rdselState = 0xFF; registersToUpdate |= 1 << DriveConfig; - cpu_irq_restore(flags); + IrqRestore(flags); } } @@ -640,10 +640,10 @@ uint32_t TmcDriverState::ReadAccumulatedStatus(uint32_t bitsToKeep) noexcept { const uint32_t mask = (enabled) ? 0xFFFFFFFF : ~(TMC_RR_SG | TMC_RR_OLA | TMC_RR_OLB); bitsToKeep &= mask; - const irqflags_t flags = cpu_irq_save(); + const irqflags_t flags = IrqSave(); const uint32_t status = accumulatedStatus; accumulatedStatus = (status & bitsToKeep) | lastReadStatus; // so that the next call to ReadAccumulatedStatus isn't missing some bits - cpu_irq_restore(flags); + IrqRestore(flags); return status & (TMC_RR_SG | TMC_RR_OT | TMC_RR_OTPW | TMC_RR_S2G | TMC_RR_OLA | TMC_RR_OLB | TMC_RR_STST) & mask; } @@ -825,7 +825,7 @@ inline void TmcDriverState::StartTransfer() noexcept } // Kick off a transfer for that register - const irqflags_t flags = cpu_irq_save(); // avoid race condition + const irqflags_t flags = IrqSave(); // avoid race condition #if TMC2660_USES_USART USART_TMC2660->US_CR = US_CR_RSTRX | US_CR_RSTTX; // reset transmitter and receiver @@ -853,7 +853,7 @@ inline void TmcDriverState::StartTransfer() noexcept SPI_TMC2660->SPI_CR = SPI_CR_SPIEN; // enable SPI #endif - cpu_irq_restore(flags); + IrqRestore(flags); } // ISR for the USART diff --git a/src/Platform/Platform.cpp b/src/Platform/Platform.cpp index 684a41f1..1b7a911f 100644 --- a/src/Platform/Platform.cpp +++ b/src/Platform/Platform.cpp @@ -1396,6 +1396,8 @@ void Platform::Spin() noexcept } if (numVinUnderVoltageEvents != previousVinUnderVoltageEvents) { + //DEBUG increased the number of d.p. +// MessageF(WarningMessage, "VIN under-voltage event (%.1fV)(%u)", (double)AdcReadingToPowerVoltage(lastVinUnderVoltageValue), lastVinUnderVoltageValue); MessageF(WarningMessage, "VIN under-voltage event (%.1fV)", (double)AdcReadingToPowerVoltage(lastVinUnderVoltageValue)); previousVinUnderVoltageEvents = numVinUnderVoltageEvents; reported = true; @@ -1905,13 +1907,13 @@ void Platform::Diagnostics(MessageType mtype) noexcept // Execute a timed square root that takes less than one millisecond static uint32_t TimedSqrt(uint64_t arg, uint32_t& timeAcc) noexcept { - cpu_irq_disable(); + IrqDisable(); asm volatile("":::"memory"); uint32_t now1 = SysTick->VAL; const uint32_t ret = isqrt64(arg); uint32_t now2 = SysTick->VAL; asm volatile("":::"memory"); - cpu_irq_enable(); + IrqEnable(); now1 &= 0x00FFFFFF; now2 &= 0x00FFFFFF; timeAcc += ((now1 > now2) ? now1 : now1 + (SysTick->LOAD & 0x00FFFFFF) + 1) - now2; @@ -2221,13 +2223,13 @@ GCodeResult Platform::DiagnosticTest(GCodeBuffer& gb, const StringRef& reply, Ou { const float angle = 0.01 * i; - cpu_irq_disable(); + IrqDisable(); asm volatile("":::"memory"); uint32_t now1 = SysTick->VAL; (void)RepRap::SinfCosf(angle); uint32_t now2 = SysTick->VAL; asm volatile("":::"memory"); - cpu_irq_enable(); + IrqEnable(); now1 &= 0x00FFFFFF; now2 &= 0x00FFFFFF; tim1 += ((now1 > now2) ? now1 : now1 + (SysTick->LOAD & 0x00FFFFFF) + 1) - now2; @@ -2245,13 +2247,13 @@ GCodeResult Platform::DiagnosticTest(GCodeBuffer& gb, const StringRef& reply, Ou for (unsigned int i = 0; i < iterations; ++i) { - cpu_irq_disable(); + IrqDisable(); asm volatile("":::"memory"); uint32_t now1 = SysTick->VAL; val = RepRap::FastSqrtf(val); uint32_t now2 = SysTick->VAL; asm volatile("":::"memory"); - cpu_irq_enable(); + IrqEnable(); now1 &= 0x00FFFFFF; now2 &= 0x00FFFFFF; tim1 += ((now1 > now2) ? now1 : now1 + (SysTick->LOAD & 0x00FFFFFF) + 1) - now2; @@ -2347,7 +2349,7 @@ GCodeResult Platform::DiagnosticTest(GCodeBuffer& gb, const StringRef& reply, Ou { const size_t length = (gb.Seen('S')) ? gb.GetUIValue() : 1024; CRC32 crc; - cpu_irq_disable(); + IrqDisable(); asm volatile("":::"memory"); uint32_t now1 = SysTick->VAL; crc.Update( @@ -2359,7 +2361,7 @@ GCodeResult Platform::DiagnosticTest(GCodeBuffer& gb, const StringRef& reply, Ou length); uint32_t now2 = SysTick->VAL; asm volatile("":::"memory"); - cpu_irq_enable(); + IrqEnable(); now1 &= 0x00FFFFFF; now2 &= 0x00FFFFFF; uint32_t tim1 = ((now1 > now2) ? now1 : now1 + (SysTick->LOAD & 0x00FFFFFF) + 1) - now2; @@ -2370,7 +2372,7 @@ GCodeResult Platform::DiagnosticTest(GCodeBuffer& gb, const StringRef& reply, Ou case (unsigned int)DiagnosticTestType::TimeGetTimerTicks: { unsigned int i = 100; - cpu_irq_disable(); + IrqDisable(); asm volatile("":::"memory"); uint32_t now1 = SysTick->VAL; do @@ -2380,7 +2382,7 @@ GCodeResult Platform::DiagnosticTest(GCodeBuffer& gb, const StringRef& reply, Ou } while (i != 0); uint32_t now2 = SysTick->VAL; asm volatile("":::"memory"); - cpu_irq_enable(); + IrqEnable(); now1 &= 0x00FFFFFF; now2 &= 0x00FFFFFF; uint32_t tim1 = ((now1 > now2) ? now1 : now1 + (SysTick->LOAD & 0x00FFFFFF) + 1) - now2; diff --git a/src/Platform/Platform.h b/src/Platform/Platform.h index 65310be4..f203e280 100644 --- a/src/Platform/Platform.h +++ b/src/Platform/Platform.h @@ -216,7 +216,7 @@ public: void Init(uint16_t val) volatile noexcept { - const irqflags_t flags = cpu_irq_save(); + const irqflags_t flags = IrqSave(); sum = (uint32_t)val * (uint32_t)numAveraged; index = 0; isValid = false; @@ -224,7 +224,7 @@ public: { readings[i] = val; } - cpu_irq_restore(flags); + IrqRestore(flags); } // Call this to put a new reading into the filter diff --git a/src/Platform/RepRap.cpp b/src/Platform/RepRap.cpp index 625f0b22..700bfbeb 100644 --- a/src/Platform/RepRap.cpp +++ b/src/Platform/RepRap.cpp @@ -2819,7 +2819,7 @@ void RepRap::StartIap(const char *filename) noexcept // Disable all IRQs SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk; // disable the system tick exception - cpu_irq_disable(); + IrqDisable(); for (size_t i = 0; i < 8; i++) { NVIC->ICER[i] = 0xFFFFFFFF; // Disable IRQs @@ -2878,7 +2878,7 @@ void RepRap::StartIap(const char *filename) noexcept __DSB(); __ISB(); - cpu_irq_enable(); + IrqEnable(); __asm volatile ("mov r3, %0" : : "r" (IAP_IMAGE_START) : "r3"); diff --git a/src/Storage/FileStore.cpp b/src/Storage/FileStore.cpp index d6eaff2e..cc82d483 100644 --- a/src/Storage/FileStore.cpp +++ b/src/Storage/FileStore.cpp @@ -170,22 +170,22 @@ bool FileStore::Close() noexcept case FileUseMode::readOnly: case FileUseMode::readWrite: { - const irqflags_t flags = cpu_irq_save(); + const irqflags_t flags = IrqSave(); if (openCount > 1) { --openCount; - cpu_irq_restore(flags); + IrqRestore(flags); return true; } else if (inInterrupt()) { closeRequested = true; - cpu_irq_restore(flags); + IrqRestore(flags); return true; } else { - cpu_irq_restore(flags); + IrqRestore(flags); return ForceClose(); } } @@ -193,7 +193,7 @@ bool FileStore::Close() noexcept case FileUseMode::invalidated: default: { - const irqflags_t flags = cpu_irq_save(); + const irqflags_t flags = IrqSave(); if (openCount > 1) { --openCount; @@ -202,7 +202,7 @@ bool FileStore::Close() noexcept { usageMode = FileUseMode::free; } - cpu_irq_restore(flags); + IrqRestore(flags); return true; } } @@ -422,9 +422,9 @@ void FileStore::Duplicate() noexcept case FileUseMode::readOnly: case FileUseMode::readWrite: { - const irqflags_t flags = cpu_irq_save(); + const irqflags_t flags = IrqSave(); ++openCount; - cpu_irq_restore(flags); + IrqRestore(flags); } break; |