diff --git a/examples/Example4-SPI_Simple_measurement/Example4-SPI_Simple_measurement.ino b/examples/Example4-SPI_Simple_measurement/Example4-SPI_Simple_measurement.ino index a12c3f1..2983fe5 100644 --- a/examples/Example4-SPI_Simple_measurement/Example4-SPI_Simple_measurement.ino +++ b/examples/Example4-SPI_Simple_measurement/Example4-SPI_Simple_measurement.ino @@ -30,11 +30,12 @@ void setup() SPI.begin(); - if (myMag.begin(csPin) == false) + while (myMag.begin(csPin) == false) { - Serial.println("MMC5983MA did not respond - check your wiring. Freezing."); - while (true) - ; + Serial.println("MMC5983MA did not respond. Retrying..."); + delay(500); + myMag.softReset(); + delay(500); } Serial.println("MMC5983MA connected"); diff --git a/examples/Example5-SPI_Digital_compass/Example5-SPI_Digital_compass.ino b/examples/Example5-SPI_Digital_compass/Example5-SPI_Digital_compass.ino index 6ce949f..205210c 100644 --- a/examples/Example5-SPI_Digital_compass/Example5-SPI_Digital_compass.ino +++ b/examples/Example5-SPI_Digital_compass/Example5-SPI_Digital_compass.ino @@ -30,11 +30,12 @@ void setup() SPI.begin(); - if (myMag.begin(csPin) == false) + while (myMag.begin(csPin) == false) { - Serial.println("MMC5983MA did not respond - check your wiring. Freezing."); - while (true) - ; + Serial.println("MMC5983MA did not respond. Retrying..."); + delay(500); + myMag.softReset(); + delay(500); } Serial.println("MMC5983MA connected"); diff --git a/examples/Example6-SPI_Fast_Continuous_measurement/Example6-SPI_Fast_Continuous_measurement.ino b/examples/Example6-SPI_Fast_Continuous_measurement/Example6-SPI_Fast_Continuous_measurement.ino index a21bbe5..2d8f068 100644 --- a/examples/Example6-SPI_Fast_Continuous_measurement/Example6-SPI_Fast_Continuous_measurement.ino +++ b/examples/Example6-SPI_Fast_Continuous_measurement/Example6-SPI_Fast_Continuous_measurement.ino @@ -45,11 +45,12 @@ void setup() pinMode(interruptPin, INPUT); attachInterrupt(digitalPinToInterrupt(interruptPin), interruptRoutine, RISING); - if (myMag.begin(csPin) == false) + while (myMag.begin(csPin) == false) { - Serial.println("MMC5983MA did not respond - check your wiring. Freezing."); - while (true) - ; + Serial.println("MMC5983MA did not respond. Retrying..."); + delay(500); + myMag.softReset(); + delay(500); } myMag.softReset(); diff --git a/library.properties b/library.properties index ba91f6e..9f19b82 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=SparkFun MMC5983MA Magnetometer Arduino Library -version=1.0.3 +version=1.1.0 author=SparkFun Electronics maintainer=SparkFun Electronics sentence=A I2C/SPI library for the MMC5983MA magnetic compass sensor. diff --git a/src/SparkFun_MMC5983MA_Arduino_Library.cpp b/src/SparkFun_MMC5983MA_Arduino_Library.cpp index d685e3c..a823cb9 100644 --- a/src/SparkFun_MMC5983MA_Arduino_Library.cpp +++ b/src/SparkFun_MMC5983MA_Arduino_Library.cpp @@ -15,7 +15,7 @@ #include "SparkFun_MMC5983MA_Arduino_Library.h" #include "SparkFun_MMC5983MA_Arduino_Library_Constants.h" -bool SFE_MMC5983MA::setShadowBit(uint8_t registerAddress, const uint8_t bitMask) +bool SFE_MMC5983MA::setShadowBit(uint8_t registerAddress, const uint8_t bitMask, bool doWrite) { uint8_t *shadowRegister = nullptr; @@ -53,13 +53,15 @@ bool SFE_MMC5983MA::setShadowBit(uint8_t registerAddress, const uint8_t bitMask) if (shadowRegister) { *shadowRegister |= bitMask; - return (mmc_io.writeSingleByte(registerAddress, *shadowRegister)); + if (doWrite) + return (mmc_io.writeSingleByte(registerAddress, *shadowRegister)); + return true; } return false; } -bool SFE_MMC5983MA::clearShadowBit(uint8_t registerAddress, const uint8_t bitMask) +bool SFE_MMC5983MA::clearShadowBit(uint8_t registerAddress, const uint8_t bitMask, bool doWrite) { uint8_t *shadowRegister = nullptr; @@ -97,7 +99,9 @@ bool SFE_MMC5983MA::clearShadowBit(uint8_t registerAddress, const uint8_t bitMas if (shadowRegister) { *shadowRegister &= ~bitMask; - return (mmc_io.writeSingleByte(registerAddress, *shadowRegister)); + if (doWrite) + return (mmc_io.writeSingleByte(registerAddress, *shadowRegister)); + return true; } return false; @@ -234,10 +238,13 @@ bool SFE_MMC5983MA::isConnected() int SFE_MMC5983MA::getTemperature() { - // Send command to device. Since TM_T clears itself we don't need to - // use the shadow register for this - we can send the command directly to the IC. - if (!mmc_io.setRegisterBit(INT_CTRL_0_REG, TM_T)) + // Set the TM_T bit to start the temperature conversion. + // Do this using the shadow register. If we do it with setRegisterBit + // (read-modify-write) we end up setting the Auto_SR_en bit too as that + // always seems to read as 1...? I don't know why. + if (!setShadowBit(INT_CTRL_0_REG, TM_T)) { + clearShadowBit(INT_CTRL_0_REG, TM_T, false); // Clear the bit - in shadow memory only SAFE_CALLBACK(errorCallback, SF_MMC5983MA_ERROR::BUS_ERROR); return -99; } @@ -249,6 +256,8 @@ int SFE_MMC5983MA::getTemperature() delay(1); } while (!mmc_io.isBitSet(STATUS_REG, MEAS_T_DONE)); + clearShadowBit(INT_CTRL_0_REG, TM_T, false); // Clear the bit - in shadow memory only + // Get raw temperature value from the IC. uint8_t result = 0; if (!mmc_io.readSingleByte(T_OUT_REG, &result)) @@ -266,9 +275,13 @@ int SFE_MMC5983MA::getTemperature() bool SFE_MMC5983MA::softReset() { - // Since SW_RST bit clears itself we don't need to to through the shadow - // register for this - we can send the command directly to the IC. - bool success = mmc_io.setRegisterBit(INT_CTRL_1_REG, SW_RST); + // Set the SW_RST bit to perform a software reset. + // Do this using the shadow register. If we do it with setRegisterBit + // (read-modify-write) we end up setting the reserved and BW_0 bits too as they + // always seems to read as 1...? I don't know why. + bool success = setShadowBit(INT_CTRL_1_REG, SW_RST); + + clearShadowBit(INT_CTRL_1_REG, SW_RST, false); // Clear the bit - in shadow memory only // The reset time is 10 msec. but we'll wait 15 msec. just in case. delay(15); @@ -320,11 +333,15 @@ bool SFE_MMC5983MA::is3WireSPIEnabled() bool SFE_MMC5983MA::performSetOperation() { - // Since SET bit clears itself we don't need to to through the shadow - // register for this - we can send the command directly to the IC. - bool success = mmc_io.setRegisterBit(INT_CTRL_0_REG, SET_OPERATION); + // Set the SET bit to perform a set operation. + // Do this using the shadow register. If we do it with setRegisterBit + // (read-modify-write) we end up setting the Auto_SR_en bit too as that + // always seems to read as 1...? I don't know why. + bool success = setShadowBit(INT_CTRL_0_REG, SET_OPERATION); + + clearShadowBit(INT_CTRL_0_REG, SET_OPERATION, false); // Clear the bit - in shadow memory only - // Wait until bit clears itself. + // Wait for the set operation to complete (500ns). delay(1); return success; @@ -332,11 +349,15 @@ bool SFE_MMC5983MA::performSetOperation() bool SFE_MMC5983MA::performResetOperation() { - // Since RESET bit clears itself we don't need to to through the shadow - // register for this - we can send the command directly to the IC. - bool success = mmc_io.setRegisterBit(INT_CTRL_0_REG, RESET_OPERATION); + // Set the RESET bit to perform a reset operation. + // Do this using the shadow register. If we do it with setRegisterBit + // (read-modify-write) we end up setting the Auto_SR_en bit too as that + // always seems to read as 1...? I don't know why. + bool success = setShadowBit(INT_CTRL_0_REG, RESET_OPERATION); - // Wait until bit clears itself. + clearShadowBit(INT_CTRL_0_REG, RESET_OPERATION, false); // Clear the bit - in shadow memory only + + // Wait for the reset operation to complete (500ns). delay(1); return success; @@ -385,6 +406,9 @@ bool SFE_MMC5983MA::isXChannelEnabled() { // Get the bit value from the shadow register since the IC does not // allow reading INT_CTRL_1_REG register. + // + // Note: this returns true when the X channel is inhibited. + // Strictly, it should be called isXChannelInhibited. return (isShadowBitSet(INT_CTRL_1_REG, X_INHIBIT)); } @@ -410,6 +434,9 @@ bool SFE_MMC5983MA::areYZChannelsEnabled() { // Get the bit value from the shadow register since the IC does not // allow reading INT_CTRL_1_REG register. + // + // Note: this returns true when the Y and Z channels are inhibited. + // Strictly, it should be called areYZChannelsInhibited. return (isShadowBitSet(INT_CTRL_1_REG, YZ_INHIBIT)); } @@ -423,28 +450,28 @@ bool SFE_MMC5983MA::setFilterBandwidth(uint16_t bandwidth) { case 800: { - success = setShadowBit(INT_CTRL_1_REG, BW0); + success = setShadowBit(INT_CTRL_1_REG, BW0, false); success &= setShadowBit(INT_CTRL_1_REG, BW1); } break; case 400: { - success = clearShadowBit(INT_CTRL_1_REG, BW0); + success = clearShadowBit(INT_CTRL_1_REG, BW0, false); success &= setShadowBit(INT_CTRL_1_REG, BW1); } break; case 200: { - success = setShadowBit(INT_CTRL_1_REG, BW0); + success = setShadowBit(INT_CTRL_1_REG, BW0, false); success &= clearShadowBit(INT_CTRL_1_REG, BW1); } break; case 100: { - success = clearShadowBit(INT_CTRL_1_REG, BW0); + success = clearShadowBit(INT_CTRL_1_REG, BW0, false); success &= clearShadowBit(INT_CTRL_1_REG, BW1); } break; @@ -522,8 +549,8 @@ bool SFE_MMC5983MA::setContinuousModeFrequency(uint16_t frequency) case 1: { // CM_FREQ[2:0] = 001 - success = clearShadowBit(INT_CTRL_2_REG, CM_FREQ_2); - success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_1); + success = clearShadowBit(INT_CTRL_2_REG, CM_FREQ_2, false); + success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_1, false); success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_0); } break; @@ -531,8 +558,8 @@ bool SFE_MMC5983MA::setContinuousModeFrequency(uint16_t frequency) case 10: { // CM_FREQ[2:0] = 010 - success = clearShadowBit(INT_CTRL_2_REG, CM_FREQ_2); - success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_1); + success = clearShadowBit(INT_CTRL_2_REG, CM_FREQ_2, false); + success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_1, false); success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_0); } break; @@ -540,8 +567,8 @@ bool SFE_MMC5983MA::setContinuousModeFrequency(uint16_t frequency) case 20: { // CM_FREQ[2:0] = 011 - success = clearShadowBit(INT_CTRL_2_REG, CM_FREQ_2); - success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_1); + success = clearShadowBit(INT_CTRL_2_REG, CM_FREQ_2, false); + success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_1, false); success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_0); } break; @@ -549,8 +576,8 @@ bool SFE_MMC5983MA::setContinuousModeFrequency(uint16_t frequency) case 50: { // CM_FREQ[2:0] = 100 - success = setShadowBit(INT_CTRL_2_REG, CM_FREQ_2); - success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_1); + success = setShadowBit(INT_CTRL_2_REG, CM_FREQ_2, false); + success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_1, false); success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_0); } break; @@ -558,8 +585,8 @@ bool SFE_MMC5983MA::setContinuousModeFrequency(uint16_t frequency) case 100: { // CM_FREQ[2:0] = 101 - success = setShadowBit(INT_CTRL_2_REG, CM_FREQ_2); - success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_1); + success = setShadowBit(INT_CTRL_2_REG, CM_FREQ_2, false); + success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_1, false); success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_0); } break; @@ -567,8 +594,8 @@ bool SFE_MMC5983MA::setContinuousModeFrequency(uint16_t frequency) case 200: { // CM_FREQ[2:0] = 110 - success = setShadowBit(INT_CTRL_2_REG, CM_FREQ_2); - success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_1); + success = setShadowBit(INT_CTRL_2_REG, CM_FREQ_2, false); + success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_1, false); success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_0); } break; @@ -576,8 +603,8 @@ bool SFE_MMC5983MA::setContinuousModeFrequency(uint16_t frequency) case 1000: { // CM_FREQ[2:0] = 111 - success = setShadowBit(INT_CTRL_2_REG, CM_FREQ_2); - success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_1); + success = setShadowBit(INT_CTRL_2_REG, CM_FREQ_2, false); + success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_1, false); success &= setShadowBit(INT_CTRL_2_REG, CM_FREQ_0); } break; @@ -585,8 +612,8 @@ bool SFE_MMC5983MA::setContinuousModeFrequency(uint16_t frequency) case 0: { // CM_FREQ[2:0] = 000 - success = clearShadowBit(INT_CTRL_2_REG, CM_FREQ_2); - success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_1); + success = clearShadowBit(INT_CTRL_2_REG, CM_FREQ_2, false); + success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_1, false); success &= clearShadowBit(INT_CTRL_2_REG, CM_FREQ_0); } break; @@ -696,8 +723,8 @@ bool SFE_MMC5983MA::setPeriodicSetSamples(const uint16_t numberOfSamples) case 25: { // PRD_SET[2:0] = 001 - success = clearShadowBit(INT_CTRL_2_REG, PRD_SET_2); - success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_1); + success = clearShadowBit(INT_CTRL_2_REG, PRD_SET_2, false); + success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_1, false); success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_0); } break; @@ -705,8 +732,8 @@ bool SFE_MMC5983MA::setPeriodicSetSamples(const uint16_t numberOfSamples) case 75: { // PRD_SET[2:0] = 010 - success = clearShadowBit(INT_CTRL_2_REG, PRD_SET_2); - success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_1); + success = clearShadowBit(INT_CTRL_2_REG, PRD_SET_2, false); + success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_1, false); success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_0); } break; @@ -714,8 +741,8 @@ bool SFE_MMC5983MA::setPeriodicSetSamples(const uint16_t numberOfSamples) case 100: { // PRD_SET[2:0] = 011 - success = clearShadowBit(INT_CTRL_2_REG, PRD_SET_2); - success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_1); + success = clearShadowBit(INT_CTRL_2_REG, PRD_SET_2, false); + success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_1, false); success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_0); } break; @@ -723,8 +750,8 @@ bool SFE_MMC5983MA::setPeriodicSetSamples(const uint16_t numberOfSamples) case 250: { // PRD_SET[2:0] = 100 - success = setShadowBit(INT_CTRL_2_REG, PRD_SET_2); - success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_1); + success = setShadowBit(INT_CTRL_2_REG, PRD_SET_2, false); + success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_1, false); success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_0); } break; @@ -732,8 +759,8 @@ bool SFE_MMC5983MA::setPeriodicSetSamples(const uint16_t numberOfSamples) case 500: { // PRD_SET[2:0] = 101 - success = setShadowBit(INT_CTRL_2_REG, PRD_SET_2); - success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_1); + success = setShadowBit(INT_CTRL_2_REG, PRD_SET_2, false); + success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_1, false); success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_0); } break; @@ -741,8 +768,8 @@ bool SFE_MMC5983MA::setPeriodicSetSamples(const uint16_t numberOfSamples) case 1000: { // PRD_SET[2:0] = 110 - success = setShadowBit(INT_CTRL_2_REG, PRD_SET_2); - success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_1); + success = setShadowBit(INT_CTRL_2_REG, PRD_SET_2, false); + success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_1, false); success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_0); } break; @@ -750,8 +777,8 @@ bool SFE_MMC5983MA::setPeriodicSetSamples(const uint16_t numberOfSamples) case 2000: { // PRD_SET[2:0] = 111 - success = setShadowBit(INT_CTRL_2_REG, PRD_SET_2); - success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_1); + success = setShadowBit(INT_CTRL_2_REG, PRD_SET_2, false); + success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_1, false); success &= setShadowBit(INT_CTRL_2_REG, PRD_SET_0); } break; @@ -759,8 +786,8 @@ bool SFE_MMC5983MA::setPeriodicSetSamples(const uint16_t numberOfSamples) case 1: { // PRD_SET[2:0] = 000 - success = clearShadowBit(INT_CTRL_2_REG, PRD_SET_2); - success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_1); + success = clearShadowBit(INT_CTRL_2_REG, PRD_SET_2, false); + success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_1, false); success &= clearShadowBit(INT_CTRL_2_REG, PRD_SET_0); } break; @@ -882,9 +909,13 @@ bool SFE_MMC5983MA::isExtraCurrentAppliedNegToPos() uint32_t SFE_MMC5983MA::getMeasurementX() { - // Send command to device. TM_M self clears so we can access it directly. - if (!mmc_io.setRegisterBit(INT_CTRL_0_REG, TM_M)) + // Set the TM_M bit to start the measurement. + // Do this using the shadow register. If we do it with setRegisterBit + // (read-modify-write) we end up setting the Auto_SR_en bit too as that + // always seems to read as 1...? I don't know why. + if (!setShadowBit(INT_CTRL_0_REG, TM_M)) { + clearShadowBit(INT_CTRL_0_REG, TM_M, false); // Clear the bit - in shadow memory only SAFE_CALLBACK(errorCallback, SF_MMC5983MA_ERROR::BUS_ERROR); return 0; } @@ -896,6 +927,8 @@ uint32_t SFE_MMC5983MA::getMeasurementX() delay(1); } while (!mmc_io.isBitSet(STATUS_REG, MEAS_M_DONE)); + clearShadowBit(INT_CTRL_0_REG, TM_M, false); // Clear the bit - in shadow memory only + uint32_t result = 0; uint8_t buffer[2] = {0}; uint8_t buffer2bit = 0; @@ -912,9 +945,13 @@ uint32_t SFE_MMC5983MA::getMeasurementX() uint32_t SFE_MMC5983MA::getMeasurementY() { - // Send command to device. TM_M self clears so we can access it directly. - if (!mmc_io.setRegisterBit(INT_CTRL_0_REG, TM_M)) + // Set the TM_M bit to start the measurement. + // Do this using the shadow register. If we do it with setRegisterBit + // (read-modify-write) we end up setting the Auto_SR_en bit too as that + // always seems to read as 1...? I don't know why. + if (!setShadowBit(INT_CTRL_0_REG, TM_M)) { + clearShadowBit(INT_CTRL_0_REG, TM_M, false); // Clear the bit - in shadow memory only SAFE_CALLBACK(errorCallback, SF_MMC5983MA_ERROR::BUS_ERROR); return 0; } @@ -926,6 +963,8 @@ uint32_t SFE_MMC5983MA::getMeasurementY() delay(1); } while (!mmc_io.isBitSet(STATUS_REG, MEAS_M_DONE)); + clearShadowBit(INT_CTRL_0_REG, TM_M, false); // Clear the bit - in shadow memory only + uint32_t result = 0; uint8_t buffer[2] = {0}; uint8_t buffer2bit = 0; @@ -942,9 +981,13 @@ uint32_t SFE_MMC5983MA::getMeasurementY() uint32_t SFE_MMC5983MA::getMeasurementZ() { - // Send command to device. TM_M self clears so we can access it directly. - if (!mmc_io.setRegisterBit(INT_CTRL_0_REG, TM_M)) + // Set the TM_M bit to start the measurement. + // Do this using the shadow register. If we do it with setRegisterBit + // (read-modify-write) we end up setting the Auto_SR_en bit too as that + // always seems to read as 1...? I don't know why. + if (!setShadowBit(INT_CTRL_0_REG, TM_M)) { + clearShadowBit(INT_CTRL_0_REG, TM_M, false); // Clear the bit - in shadow memory only SAFE_CALLBACK(errorCallback, SF_MMC5983MA_ERROR::BUS_ERROR); return 0; } @@ -956,6 +999,8 @@ uint32_t SFE_MMC5983MA::getMeasurementZ() delay(1); } while (!mmc_io.isBitSet(STATUS_REG, MEAS_M_DONE)); + clearShadowBit(INT_CTRL_0_REG, TM_M, false); // Clear the bit - in shadow memory only + uint32_t result = 0; uint8_t buffer[3] = {0}; @@ -970,11 +1015,15 @@ uint32_t SFE_MMC5983MA::getMeasurementZ() bool SFE_MMC5983MA::getMeasurementXYZ(uint32_t *x, uint32_t *y, uint32_t *z) { - // Send command to device. TM_M self clears so we can access it directly. - bool success = mmc_io.setRegisterBit(INT_CTRL_0_REG, TM_M); + // Set the TM_M bit to start the measurement. + // Do this using the shadow register. If we do it with setRegisterBit + // (read-modify-write) we end up setting the Auto_SR_en bit too as that + // always seems to read as 1...? I don't know why. + bool success = setShadowBit(INT_CTRL_0_REG, TM_M); if (!success) { + clearShadowBit(INT_CTRL_0_REG, TM_M, false); // Clear the bit - in shadow memory only SAFE_CALLBACK(errorCallback, SF_MMC5983MA_ERROR::BUS_ERROR); return false; } @@ -986,6 +1035,8 @@ bool SFE_MMC5983MA::getMeasurementXYZ(uint32_t *x, uint32_t *y, uint32_t *z) delay(1); } while (!mmc_io.isBitSet(STATUS_REG, MEAS_M_DONE)); + clearShadowBit(INT_CTRL_0_REG, TM_M, false); // Clear the bit - in shadow memory only + return (readFieldsXYZ(x, y, z)); } @@ -1017,6 +1068,10 @@ bool SFE_MMC5983MA::readFieldsXYZ(uint32_t *x, uint32_t *y, uint32_t *z) bool SFE_MMC5983MA::clearMeasDoneInterrupt(uint8_t measMask) { - measMask &= (MEAS_T_DONE | MEAS_M_DONE); // Ensure only the Meas_T_Done and Meas_M_Done interrupts can be cleared - return (mmc_io.setRegisterBit(STATUS_REG, measMask)); // Writing 1 into these bits will clear the corresponding interrupt + // Ensure only the Meas_T_Done and Meas_M_Done interrupts can be cleared + measMask &= (MEAS_T_DONE | MEAS_M_DONE); + + // Writing 1 into these bits will clear the corresponding interrupt + // Read-modify-write is OK here + return (mmc_io.setRegisterBit(STATUS_REG, measMask)); } \ No newline at end of file diff --git a/src/SparkFun_MMC5983MA_Arduino_Library.h b/src/SparkFun_MMC5983MA_Arduino_Library.h index a07b573..d0faa13 100644 --- a/src/SparkFun_MMC5983MA_Arduino_Library.h +++ b/src/SparkFun_MMC5983MA_Arduino_Library.h @@ -42,11 +42,11 @@ class SFE_MMC5983MA uint8_t internalControl3 = 0x0; } memoryShadow; - // Sets register bit(s) on memory shadows and then registers - bool setShadowBit(uint8_t registerAddress, const uint8_t bitMask); + // Sets register bit(s) on memory shadows and then registers (if doWrite is true) + bool setShadowBit(uint8_t registerAddress, const uint8_t bitMask, bool doWrite = true); - // Clears register bit(s) on memory shadows and then registers - bool clearShadowBit(uint8_t registerAddress, const uint8_t bitMask); + // Clears register bit(s) on memory shadows and then registers (if doWrite is true) + bool clearShadowBit(uint8_t registerAddress, const uint8_t bitMask, bool doWrite = true); // Checks if a specific bit is set on a register memory shadow bool isShadowBitSet(uint8_t registerAddress, const uint8_t bitMask); @@ -121,6 +121,8 @@ class SFE_MMC5983MA bool disableXChannel(); // Checks if X channel output is enabled + // Note: this returns true when the X channel is inhibited. + // Strictly, it should be called isXChannelInhibited. bool isXChannelEnabled(); // Enables Y and Z channels outputs @@ -130,6 +132,8 @@ class SFE_MMC5983MA bool disableYZChannels(); // Checks if YZ channels outputs are enabled + // Note: this returns true when the Y and Z channels are inhibited. + // Strictly, it should be called areYZChannelsInhibited. bool areYZChannelsEnabled(); // Sets decimation filter bandwidth. Allowed values are 800, 400, 200 or 100. Defaults to 100 on invalid values.