diff options
author | David Crocker <dcrocker@eschertech.com> | 2021-11-10 17:51:56 +0300 |
---|---|---|
committer | David Crocker <dcrocker@eschertech.com> | 2021-11-10 17:51:56 +0300 |
commit | e7795870eb998db2cd4b4fdee703111812be84c0 (patch) | |
tree | dbaf4c33b6b678dd4b067c3ca686539deb834f90 | |
parent | 06dc58407ac9a3ea9552cc96d5b77822551c554b (diff) |
Check that accelerometer INT1 is working when starting to collect data
-rw-r--r-- | src/Accelerometers/Accelerometers.cpp | 45 | ||||
-rw-r--r-- | src/Accelerometers/LIS3DH.cpp | 10 | ||||
-rw-r--r-- | src/Accelerometers/LIS3DH.h | 4 |
3 files changed, 55 insertions, 4 deletions
diff --git a/src/Accelerometers/Accelerometers.cpp b/src/Accelerometers/Accelerometers.cpp index 949937b4..eb56a0fa 100644 --- a/src/Accelerometers/Accelerometers.cpp +++ b/src/Accelerometers/Accelerometers.cpp @@ -73,6 +73,8 @@ static unsigned int numLocalRunsCompleted = 0; static unsigned int lastRunNumSamplesReceived = 0; static uint8_t axisLookup[3]; static bool axisInverted[3]; +static volatile bool successfulStart = false; +static volatile bool failedStart = false; static IoPort spiCsPort; static IoPort irqPort; @@ -112,9 +114,11 @@ static uint8_t TranslateAxes(uint8_t axes) noexcept unsigned int numOverflows = 0; const uint16_t mask = (1u << resolution) - 1; const int decimalPlaces = GetDecimalPlaces(resolution); + bool recordFailedStart = false; if (accelerometer->StartCollecting(TranslateAxes(axesRequested))) { + successfulStart = true; uint16_t dataRate = 0; do { @@ -198,9 +202,13 @@ static uint8_t TranslateAxes(uint8_t axes) noexcept f->Write(temp.c_str()); } } - else if (f != nullptr) + else { - f->Write("Failed to start accelerometer\n"); + recordFailedStart = true; + if (f != nullptr) + { + f->Write("Failed to start accelerometer\n"); + } } if (f != nullptr) @@ -214,6 +222,10 @@ static uint8_t TranslateAxes(uint8_t axes) noexcept // Wait for another command accelerometerFile = nullptr; + if (recordFailedStart) + { + failedStart = true; + } } } } @@ -465,7 +477,6 @@ GCodeResult Accelerometers::StartAccelerometer(GCodeBuffer& gb, const StringRef& temp.cat('\n'); f->Write(temp.c_str()); } - accelerometerFile = f; # if SUPPORT_CAN_EXPANSION if (device.IsRemote()) @@ -475,10 +486,12 @@ GCodeResult Accelerometers::StartAccelerometer(GCodeBuffer& gb, const StringRef& expectedRemoteAxes = axes; numRemoteOverflows = 0; + accelerometerFile = f; const GCodeResult rslt = CanInterface::StartAccelerometer(device, axes, numSamples, mode, gb, reply); if (rslt > GCodeResult::warning) { accelerometerFile->Close(); + accelerometerFile = nullptr; MassStorage::Delete(accelerometerFileName.c_str(), false); reprap.GetExpansion().AddAccelerometerRun(device.boardAddress, 0); } @@ -486,8 +499,32 @@ GCodeResult Accelerometers::StartAccelerometer(GCodeBuffer& gb, const StringRef& } # endif + successfulStart = false; + failedStart = false; + accelerometerFile = f; accelerometerTask->Give(); - return GCodeResult::ok; + const uint32_t startTime = millis(); + do + { + delay(5); + if (successfulStart) + { + return GCodeResult::ok; + } + } while (!failedStart && millis() - startTime < 1000); + + reply.copy("Failed to start accelerometer data collection"); + if (accelerometer->HasInterruptError()) + { + reply.cat(": INT1 error"); + } + if (accelerometerFile != nullptr) + { + accelerometerFile->Close(); + accelerometerFile = nullptr; + MassStorage::Delete(accelerometerFileName.c_str(), false); + } + return GCodeResult::error; } bool Accelerometers::HasLocalAccelerometer() noexcept diff --git a/src/Accelerometers/LIS3DH.cpp b/src/Accelerometers/LIS3DH.cpp index 4fd80be6..6b0a8e25 100644 --- a/src/Accelerometers/LIS3DH.cpp +++ b/src/Accelerometers/LIS3DH.cpp @@ -178,6 +178,16 @@ bool LIS3DH:: StartCollecting(uint8_t axes) noexcept } totalNumRead = 0; + + // Before we enable data collection, check that the interrupt line is low + pinMode(int1Pin, INPUT); // make sure we can read the interrupt pin + delayMicroseconds(5); + interruptError = digitalRead(int1Pin); + if (interruptError) + { + return false; + } + const bool ok = WriteRegister(LisRegister::Ctrl_0x20, ctrlReg_0x20 | (axes & 7)); return ok && attachInterrupt(int1Pin, Int1Interrupt, InterruptMode::rising, CallbackParameter(this)); } diff --git a/src/Accelerometers/LIS3DH.h b/src/Accelerometers/LIS3DH.h index 65ed8105..22fe4751 100644 --- a/src/Accelerometers/LIS3DH.h +++ b/src/Accelerometers/LIS3DH.h @@ -43,6 +43,9 @@ public: // Used by the ISR void Int1Isr() noexcept; + // Used by diagnostics + bool HasInterruptError() const noexcept { return interruptError; } + private: enum class LisRegister : uint8_t { @@ -65,6 +68,7 @@ private: uint32_t lastInterruptTime; uint32_t totalNumRead; bool is3DSH; + bool interruptError; uint8_t currentAxis; uint8_t ctrlReg_0x20; Pin int1Pin; |