diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 00bb42d..759b8d3 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -6,25 +6,25 @@ jobs: Test: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v4 - name: Cache pip - uses: actions/cache@v2 + uses: actions/cache@v4 with: path: ~/.cache/pip key: ${{ runner.os }}-pip-${{ hashFiles('**/requirements.txt') }} restore-keys: | ${{ runner.os }}-pip- - name: Cache PlatformIO - uses: actions/cache@v2 + uses: actions/cache@v4 with: path: ~/.platformio key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }} - name: Set up Python - uses: actions/setup-python@v2 + uses: actions/setup-python@v5 - name: Install PlatformIO run: | python -m pip install --upgrade pip pip install --upgrade platformio - name: Run PlatformIO - run: platformio ci --lib="." --board=uno --board=megaatmega2560 examples/MS5837_Example/*.ino \ No newline at end of file + run: platformio ci --lib="." --board=uno --board=megaatmega2560 examples/MS5837_Example/*.ino diff --git a/src/MS5837.cpp b/src/MS5837.cpp index 3431e81..dda33df 100644 --- a/src/MS5837.cpp +++ b/src/MS5837.cpp @@ -16,9 +16,10 @@ const uint8_t MS5837::MS5837_30BA = 0; const uint8_t MS5837::MS5837_02BA = 1; const uint8_t MS5837::MS5837_UNRECOGNISED = 255; -const uint8_t MS5837_02BA01 = 0x00; // Sensor version: From MS5837_02BA datasheet Version PROM Word 0 -const uint8_t MS5837_02BA21 = 0x15; // Sensor version: From MS5837_02BA datasheet Version PROM Word 0 -const uint8_t MS5837_30BA26 = 0x1A; // Sensor version: From MS5837_30BA datasheet Version PROM Word 0 +// context: https://github.com/ArduPilot/ardupilot/pull/29122#issuecomment-2877269114 +const uint16_t MS5837_02BA_MAX_SENSITIVITY = 49000; +const uint16_t MS5837_02BA_30BA_SEPARATION = 37000; +const uint16_t MS5837_30BA_MIN_SENSITIVITY = 26000; MS5837::MS5837() { fluidDensity = 1029; @@ -57,25 +58,24 @@ bool MS5837::init(TwoWire &wirePort) { return false; // CRC fail } - uint8_t version = (C[0] >> 5) & 0x7F; // Extract the sensor version from PROM Word 0 - - // Set _model according to the sensor version - if (version == MS5837_02BA01) + // PROM Word 1 represents the sensor's pressure sensitivity calibration + // Set _model according to the experimental pressure sensitivity thresholds + if (C[1] < MS5837_30BA_MIN_SENSITIVITY || C[1] > MS5837_02BA_MAX_SENSITIVITY) { - _model = MS5837_02BA; + _model = MS5837_UNRECOGNISED; } - else if (version == MS5837_02BA21) + else if (C[1] > MS5837_02BA_30BA_SEPARATION) { _model = MS5837_02BA; } - else if (version == MS5837_30BA26) - { - _model = MS5837_30BA; - } else { - _model = MS5837_UNRECOGNISED; + _model = MS5837_30BA; } + + // TODO: extract and store/report sensor package type from bits 11-5 of PROM Word 0, + // per https://github.com/ArduPilot/ardupilot/pull/29122#pullrequestreview-2837597764 + // The sensor has passed the CRC check, so we should return true even if // the sensor version is unrecognised. // (The MS5637 has the same address as the MS5837 and will also pass the CRC check)