Merge pull request 'feature/ms5611-support' (#3) from feature/ms5611-support into main

Reviewed-on: https://git.intern.spaceteamaachen.de/ALPAKA/driver-ms5607/pulls/3
Reviewed-by: carlwachter <carlwachter@noreply.git.intern.spaceteamaachen.de>
This commit is contained in:
carlwachter 2024-05-30 11:12:29 +00:00
commit 3a0d38bf7a
6 changed files with 483 additions and 355 deletions

View File

@ -1,9 +1,10 @@
# Driver for the MS5607 pressure sensor
# Driver for the MS56xx pressure sensor series
## Usage
1. The constructor takes an SpiDevice pointer and an instance from the OsrLevel enum
2. The OsrLevel enum stores the possible values for the OSR (how fine the sensor measures or sth.)
1. Initialize sensor with `init`.
2. Read data with `getPressure` or `getTemperature`.
3. Enjoy life.
## TODO

View File

@ -1,123 +0,0 @@
#ifndef STA_SENSORS_MS5607_HPP
#define STA_SENSORS_MS5607_HPP
#include<sta/spi/device.hpp>
#include<sta/endian.hpp>
#include<sta/stm32/delay.hpp>
namespace sta {
// Class to represent a MS5607 pressure sensor which is used with SPI
class MS5607 {
public:
// Different OSR levels for the sensor
enum OsrLevel {
_256 = 0,
_512 = 1,
_1024 = 2,
_2048 = 3,
_4096 = 4
};
MS5607(SpiDevice* device, OsrLevel osr=OsrLevel::_1024);
// Request Calculation of uncompensated pressure
// Takes a few ms -> Call, then do sth. else, then get Pressure with function
// If calculation already running, do nothing
void requestAdcReadout(uint32_t curTime);
// Function to get Pressure
// Parameter should be Temperature in Celsius * 100 (e.g. 20.3 deg. C -> 2030)
// If currently still processing, use old value
// If currently not processing, start processing to minimize potential waiting times
int32_t getPressure(int32_t temp, uint32_t curTime);
// --- DEPRECATED ---
// Parameterless version of function above
// Calls getTemperature, to get temp
// NOT RECOMMENDED
int32_t getPressure();
// Getter for temperature
// Deprecated because of time constrains
// NOT RECOMMENDED
int32_t getTemperature();
// --- DEPRECATED ---
void changeOsrLevel(OsrLevel newOsr) {
// Don't I need to write this to the sensor?
this->osr_ = newOsr;
}
private:
// Helper method to keep code clean
void pulseCS(uint32_t ms=1) {
this->device_->endTransmission();
sta::delayMs(ms);
this->device_->beginTransmission();
}
// Last Pressure Value measured; Used to give any output if still calculating ADC
int32_t lastPresVal;
// Value to store, when adc was started
// On STM32 with HAL_GetTick() (Gives ms since startup)
uint32_t adcStartTime;
// To prevent calculation of adc without reading value
bool presRead;
// STA internal object for SPi abstraction
SpiDevice* device_;
OsrLevel osr_;
// 6 Different constants; Includes Offsets, references etc.
uint16_t sens, off, tcs, tco, t_ref, tempsens;
// All possible commands to send to the sensor
enum Operations {
RESET = 0x1E,
READ_PROM = 0xA2,
D1_CONVERSION = 0x40,
D2_CONVERSION = 0x50,
ADC_RESULT = 0x00
};
// Request pure ADC converted values from the sensor
// Calculations with offset required
uint32_t readPressure();
// Read temp should not be used, rather give temp from e.g. SCA3300 as parameter to readPres
uint32_t readTemp();
// Calculate pure ADC values to final pressure/temperature values
int32_t calculatePressure(uint32_t d1, int32_t dT);
int32_t calculateTemperature(uint32_t d2);
int32_t reverseTempCalc(int32_t temp);
void reset();
void readPROM();
// Constants for waiting
const uint32_t RESET_DELAY = 2800; // in uS
// Function to get the delay times needed for different OSR Levels
// Values not found in datasheet (facepalm)
// Thus partly googled, partly tested out
static uint8_t delayTimes(OsrLevel level) {
switch (level) {
case _256:
return 1;
case _512:
return 2;
case _1024:
return 3;
case _2048:
return 5;
case _4096:
return 10;
}
}
};
}
#endif // ifndef STA_SENSORS_MS5607_HPP

View File

@ -1,6 +0,0 @@
// Needed for sta/endian.hpp
#define STA_MCU_LITTLE_ENDIAN
// Needed for sta/stm32/delay.hpp
#define STA_PLATFORM_STM32
#define STA_STM32_DELAY_US_TIM

View File

@ -0,0 +1,262 @@
#ifndef STA_SENSORS_MS5607_HPP
#define STA_SENSORS_MS5607_HPP
#include <sta/bus/spi/device.hpp>
#include <sta/bus/i2c/device.hpp>
#include <sta/time.hpp>
#include <sta/endian.hpp>
// Important: The pin CSB shall be connected to VDD or GND (do not leave unconnected!).
/**
* @brief MS56xx address when the CS pin is connected to GND.
*
*/
#define MS56XX_ADDRESS_CS_LOW (uint8_t)0x77
/**
* @brief MS56xx address when the CS pin is connected to VDD.
*
*/
#define MS56XX_ADDRESS_CS_HIGH (uint8_t)0x76
namespace sta
{
/**
* @brief Driver class for communicating with the MS56xx pressure sensor via SPI.
*
*/
class MS56xx {
public:
/**
* @brief Signature for delay msec function.
*/
using DelayUsFunc = void (*)(uint32_t);
/**
* @brief Represents the two different supported sensors.
*
*/
enum Version
{
_MS5611,
_MS5607
};
/**
* @brief Different OSR levels for the sensor
*
*/
enum OsrLevel {
_256 = 0,
_512 = 1,
_1024 = 2,
_2048 = 3,
_4096 = 4
};
/**
* @brief Different units supported by the pressure sensor.
*
*/
enum Unit
{
hPa,
Pa,
mbar
};
/**
* @brief The types of physical interfaces used for communication with the sensor.
*
*/
enum Intf
{
SPI,
I2C
};
/**
* @brief All possible commands to send to the sensor
*
*/
enum Operations
{
RESET = 0x1E,
READ_PROM = 0xA0,
D1_CONVERSION = 0x40,
D2_CONVERSION = 0x50,
ADC_RESULT = 0x00
};
/**
* @brief Represents the two datatypes available for this sensor.
*
*/
enum DataType
{
PRESSURE,
TEMPERATURE
};
/**
* @brief SPI driver for the MS56xx pressure sensor series.
*
* @param device The SPI device for bus communication.
* @param version The version of the sensor that the driver is used for.
* @param delay Function for triggering microsecond delays.
* @param osr The oversampling rate for the sensor.
*
* @note Set PS pin to low for SPI. Maximum SPI frequency 20MHz, mode 0 and 3 are supported.
*/
MS56xx(SPIDevice * device, Version version, DelayUsFunc delay, OsrLevel osr = OsrLevel::_1024);
/**
* @brief I2C driver for the MS56xx pressure sensor series.
*
* @param device The I2C device for bus communication.
* @param version The version of the sensor that the driver is used for.
* @param delay Function for triggering microsecond delays.
* @param osr The oversampling rate for the sensor.
*
* @note Set PS pin to high for I2C. Chip select pin represents LSB of address.
*/
MS56xx(I2CDevice * device, Version version, DelayUsFunc delay, OsrLevel osr = OsrLevel::_1024);
/**
* @brief Initialize the driver. Computes the pressure value at altitude 0.
*
* @return True if successful, false otherwise.
*/
bool init();
/**
* @brief Set the oversampling rate.
*
* @param osr The new oversampling rate.
*/
void setOsr(OsrLevel osr);
/**
* @brief Reads the current pressure value from the sensor. Obtains the temperature value from the interal sensor.
*
* @param unit Specifies the unit for the pressure measurement. Default is hPa.
* @return float The measured value in the specified unit.
*/
float getPressure(Unit unit = Unit::hPa);
/**
* @brief Reads the current temperature value from the sensor.
*
* @return float The measured temperature.
*/
float getTemperature();
/**
* @brief Provide a reference pressure value at a reference altitude in order to estimate the sealevel pressure.
*
* @param pressRef The reference pressure value measured at a reference altitude.
* @param altRef The reference altitude for the reference pressure.
* @param unit The unit of the provided pressure value.
*/
void setPressureReference(float pressRef, float altRef, Unit unit = Unit::hPa);
/**
* @brief Estimate the current altitude based on the pressure readings.
*
* @return float The altitude estimate in meters.
*/
float getAltitudeEstimate();
private:
/**
* @brief Reset the sensor.
*
*/
void reset();
/**
* @brief Request an ADC readout from the sensor.
*
* @param type The type of data to read.
*/
void requestData(DataType type);
/**
* @brief Read all constants from the PROM
*
*/
void readPROM();
/**
* @brief Initialize the constants used for conversion.
*
* @note This code was taken from https://github.com/RobTillaart/MS5611
*
*/
void initConstants();
/**
* @brief Convert the pressure value given in Pa to a different unit.
*
* @param pressure A pressure value in Pa.
* @param unit The desired unit.
* @return float Returns the converted value.
*/
float convertPressure(float pressure, Unit unit);
/**
* @brief Small helper function for converting a uint8_t buffer to a single uint16_t.
*
* @param buffer A uint8_t of size 2. More bytes will be ignored.
* @return uint16_t A single uint16_t containing the first buffer value as MSB and the second as LSB.
*/
uint16_t uint_8BufferTouint16_t(uint8_t* buffer);
/**
* @brief Function to get the delay times needed for different OSR Levels
*
* @param level The oversampling rate chosen
* @return uint32_t Returs the delay time in uS.
*/
uint32_t osrDelay();
private:
/**
* @brief Send a command to the sensor via the bus.
*
* @param command The command to send.
* @return true if successful, false otherwise.
*/
bool busCommand(uint8_t command);
/**
* @brief Read data from one of the sensor's registers.
*
* @param reg The register to read from.
* @param buffer The buffer to write the received data to.
* @param length The number of bytes to read from the register.
* @return true if successful, false otherwise.
*/
bool busRead(uint8_t reg, uint8_t * buffer, size_t length);
private:
// STA internal object for SPi abstraction
Device * device_;
Version version_;
Version type_;
DelayUsFunc delay_;
OsrLevel osr_;
Intf intf_;
// Pressure at sealevel. Use the standard atmosphere per default.
float sealevel_ = 1013.25;
// The different constants; Includes Offsets, references etc.
float C_[8];
// Constants for waiting
const uint32_t RESET_DELAY = 2800; // in uS
};
}
#endif // ifndef STA_SENSORS_MS5607_HPP

View File

@ -1,223 +0,0 @@
#include "sta/MS5607.hpp"
namespace sta {
// Forward declaration
uint16_t uint_8BufferTouint16_t(uint8_t* buffer);
MS5607::MS5607(SpiDevice* device, OsrLevel level) {
this->device_ = device;
this->osr_ = level;
this->lastPresVal = -1;
this->adcStartTime = -1;
this->presRead = true;
// Reset device on start-up
this->reset();
// Read the PROM e.g. constants
this->readPROM();
}
void MS5607::requestAdcReadout(uint32_t time) {
// Get current state of calculation
if (time-adcStartTime < delayTimes(this->osr_) || !presRead) {
// Time since last adc command is not enough
return;
}
this->device_->beginTransmission();
this->device_->transfer(MS5607::Operations::D1_CONVERSION + 2*this->osr_);
this->device_->endTransmission();
adcStartTime = time;
presRead = false;
}
int32_t MS5607::getPressure(int32_t temp, uint32_t time) {
if (time-adcStartTime < delayTimes(this->osr_) || presRead) {
// Time since last adc command is not enough
return lastPresVal;
}
uint8_t buffer[3] = { 0 };
this->device_->beginTransmission();
this->device_->transfer(MS5607::Operations::ADC_RESULT);
this->device_->receive(buffer, 3);
this->device_->endTransmission();
this->presRead = true;
uint32_t d1_val = buffer[0] << 16 | buffer[1] << 8 | buffer[2];
this->requestAdcReadout(time);
return calculatePressure(d1_val, reverseTempCalc(temp));
}
int32_t MS5607::reverseTempCalc(int32_t temp) {
return this->tempsens;
}
// DEPRECATED
int32_t MS5607::getPressure() {
// Get pure ADC value from the sensor
uint32_t d1 = readPressure();
// Since pressure is temp-dependant, temperature needs to be polled
// Could be too costly timewise, since 8ms is needed for the ADC
// May need future optimisation
uint32_t d2 = readTemp();
int32_t dT = d2 - ( ((uint32_t)this->t_ref) << 8);
return calculatePressure(d1, dT);
}
// DON'T USE
uint32_t MS5607::readPressure() {
// Request pressure value conversion
this->device_->beginTransmission();
this->device_->transfer(MS5607::Operations::D1_CONVERSION + 2*this->osr_);
this->device_->endTransmission();
// Wait for ADC to finish
// Could do sth. else and schedule continuation with scheduler in RTOS
// TODO: Find out min
sta::delayMs(10);
// Request readout of ADC value
uint8_t d1Arr[3];
this->device_->beginTransmission();
this->device_->transfer(MS5607::Operations::ADC_RESULT);
this->device_->receive(d1Arr, 3);
this->device_->endTransmission();
// Convert into best possible type
uint32_t res = 0;
// Shifting may not be necessary, but idk w/o testing
res |= d1Arr[0] | (d1Arr[1] << 8) | (d1Arr[2] << 16);
return res;
}
// Calculations from the Datasheet
// Probably problems with type conversions
// If we used Rust...
int32_t MS5607::calculatePressure(uint32_t d1, int32_t dT) {
int64_t offset = ( ((uint64_t)this->off) << 17) + ( ( ((uint64_t)this->tco) * dT ) >> 6);
int64_t sensitivity = ( ((uint64_t)this->sens) << 16) + ( ( ((uint64_t)this->tcs) * dT ) >> 7);
int32_t pres = ( (( ((uint64_t)d1) * sensitivity) >> 21) - offset ) >> 15;
return pres;
}
// NOT RECOMMENDED
// USE TEMP FROM SCA3300 OR STH. ELSE
int32_t MS5607::getTemperature() {
// Get pure ADC value from the sensor
uint32_t d2 = readTemp();
return calculateTemperature(d2);
}
// OLD; DON'T USE
uint32_t MS5607::readTemp() {
// Request ADC conversion of temperature
this->device_->beginTransmission();
this->device_->transfer(MS5607::Operations::D2_CONVERSION + 2*this->osr_);
this->device_->endTransmission();
// Wait for ADC to finish
// Could do sth. else and schedule continuation with scheduler in RTOS
// TODO: Test out min
sta::delayMs(10);
// Request ADC readout
uint8_t d2Arr[3];
this->device_->beginTransmission();
this->device_->transfer(MS5607::Operations::ADC_RESULT);
this->device_->receive(d2Arr, 3);
this->device_->endTransmission();
// Convert into best possible type
uint32_t res = 0;
// Shifting may be unnecessary? Don't know really w/o testing
res |= d2Arr[0] | d2Arr[1] << 8 | d2Arr[2] << 16;
return res;
}
// Calculations from the Datasheet
// Probably problems with type conversions
// If we used Rust...
int32_t MS5607::calculateTemperature(uint32_t d2) {
int32_t dT = d2 - ( ((uint32_t)this->t_ref) << 8);
int32_t temp = 2000 + ((dT * ((uint32_t)this->tempsens)) >> 23);
// Further calculations for low (<20) and very low (<(-15)) could be possible
// But I don't know whether they are necessary
return temp;
}
// Reset sequence as described in datasheet
void MS5607::reset() {
this->device_->beginTransmission();
this->device_->transfer(MS5607::Operations::RESET);
this->device_->endTransmission();
delayUs(MS5607::RESET_DELAY);
}
// Read all constants from the PROM
// May be moved to be called in reset() function in future
// Request value x -> Read value x; Then request value y etc.
// Could be optimized; Not as important since only needed once at start-up
void MS5607::readPROM() {
this->device_->beginTransmission();
this->device_->transfer(Operations::READ_PROM);
uint8_t sensArr[2];
this->device_->receive(sensArr, 2);
this->sens = uint_8BufferTouint16_t(sensArr);
pulseCS();
this->device_->transfer(Operations::READ_PROM+2);
uint8_t offArr[2];
this->device_->receive(offArr, 2);
this->off = uint_8BufferTouint16_t(offArr);
pulseCS();
this->device_->transfer(Operations::READ_PROM+4);
uint8_t tcsArr[2];
this->device_->receive(tcsArr, 2);
this->sens = uint_8BufferTouint16_t(sensArr);
pulseCS();
this->device_->transfer(Operations::READ_PROM+6);
uint8_t tcoArr[2];
this->device_->receive(tcoArr, 2);
this->tco = uint_8BufferTouint16_t(tcoArr);
pulseCS();
this->device_->transfer(Operations::READ_PROM+8);
uint8_t t_refArr[2];
this->device_->receive(t_refArr, 2);
this->t_ref = uint_8BufferTouint16_t(t_refArr);
pulseCS();
this->device_->transfer(Operations::READ_PROM+0xA);
uint8_t tempsensArr[2];
this->device_->receive(tempsensArr, 2);
this->tempsens = uint_8BufferTouint16_t(tempsensArr);
this->device_->endTransmission();
}
// Helper function:
// Take first bytes from buffer, swap them and store those in uint16_t
// Swap may not be necessary
uint16_t uint_8BufferTouint16_t(uint8_t* buffer) {
return (buffer[0] << 8) | buffer[1];
}
}

217
src/MS56xx.cpp Normal file
View File

@ -0,0 +1,217 @@
#include <sta/drivers/MS56xx.hpp>
#include <sta/debug/assert.hpp>
#include <sta/debug/debug.hpp>
#include <sta/lang.hpp>
#include <cmath>
namespace sta
{
MS56xx::MS56xx(SPIDevice * device, Version version, DelayUsFunc delay, OsrLevel osr /* = OsrLevel::_1024 */)
: device_{device},
version_{version},
delay_{delay},
osr_{osr},
intf_{Intf::SPI},
C_{}
{
STA_ASSERT(device != nullptr);
}
MS56xx::MS56xx(I2CDevice * device, Version version, DelayUsFunc delay, OsrLevel osr /* = OsrLevel::_1024 */)
: device_{device},
version_{version},
delay_{delay},
osr_{osr},
intf_{Intf::I2C},
C_{}
{
STA_ASSERT(device != nullptr);
}
bool MS56xx::init()
{
// Reset device on start-up
this->reset();
this->initConstants();
// Read the PROM e.g. constants
this->readPROM();
return true;
}
void MS56xx::setOsr(OsrLevel osr)
{
osr_ = osr;
}
void MS56xx::reset()
{
busCommand(MS56xx::Operations::RESET);
delay_(MS56xx::RESET_DELAY);
}
void MS56xx::requestData(DataType type)
{
Operations op = type == DataType::PRESSURE ? D1_CONVERSION : D2_CONVERSION;
// Request the ADC to read new data.
busCommand(op + 2*this->osr_);
delay_(osrDelay());
}
float MS56xx::getPressure(Unit unit /* = Unit::hPa */)
{
requestData(TEMPERATURE);
uint8_t buffer[3] = { 0x00, 0x00, 0x00 };
busRead(MS56xx::Operations::ADC_RESULT, buffer, 3);
uint32_t D2 = buffer[0] << 16 | buffer[1] << 8 | buffer[2];
float dT_ = D2 - C_[5];
requestData(PRESSURE);
busRead(MS56xx::Operations::ADC_RESULT, buffer, 3);
uint32_t D1 = buffer[0] << 16 | buffer[1] << 8 | buffer[2];
float offset = C_[2] + dT_ * C_[4];
float sens = C_[1] + dT_ * C_[3];
// The pressure in Pa.
float pressure = (D1 * sens * 4.76837158203125E-7 - offset) * 3.0517578125E-5;
// Convert to desired unit.
pressure = convertPressure(pressure, unit);
return pressure;
}
float MS56xx::getTemperature()
{
requestData(TEMPERATURE);
uint8_t buffer[3] = { 0x00, 0x00, 0x00 };
busRead(MS56xx::Operations::ADC_RESULT, buffer, 3);
uint32_t D2 = buffer[0] << 16 | buffer[1] << 8 | buffer[2];
float dT_ = D2 - C_[5];
float temperature = (2000 + dT_ * C_[6]) * 0.01;
return temperature;
}
void MS56xx::setPressureReference(float pressRef, float altRef, Unit unit /* = Unit::hPa */)
{
// Taken from: https://cdn-shop.adafruit.com/datasheets/BST-BMP180-DS000-09.pdf, page 17.
sealevel_ = pressRef / (std::pow((1 - altRef / 44330), 5.255));
}
float MS56xx::getAltitudeEstimate()
{
float pressure = getPressure(Unit::hPa);
// Taken from: https://cdn-shop.adafruit.com/datasheets/BST-BMP180-DS000-09.pdf, page 16
float altitude = 44330 * (1 - std::pow(pressure / sealevel_, 1 / 5.255));
return altitude;
}
void MS56xx::readPROM() {
uint8_t buffer[2];
for (size_t i = 0; i < 7; i++)
{
busRead(Operations::READ_PROM + i*2, buffer, 2);
C_[i] *= uint_8BufferTouint16_t(buffer);
}
}
void MS56xx::initConstants()
{
C_[0] = 1;
switch (version_)
{
case _MS5607:
C_[1] = 65536L;
C_[2] = 131072;
C_[3] = 0.0078125;
C_[4] = 0.015625;
C_[5] = 256;
C_[6] = 1.1920928955078125E-7;
break;
case _MS5611:
C_[1] = 32768L;
C_[2] = 65536L;
C_[3] = 3.90625E-3;
C_[4] = 0.0078125;
C_[5] = 256;
C_[6] = 1.1920928955078125E-7;
default:
break;
}
}
inline float MS56xx::convertPressure(float pressure, Unit unit)
{
switch (unit)
{
case Unit::mbar:
return pressure / 100.0f;
case Unit::hPa:
return pressure / 100.0f;
case Unit::Pa:
return pressure;
default:
STA_UNREACHABLE();
break;
}
}
inline uint16_t MS56xx::uint_8BufferTouint16_t(uint8_t* buffer) {
return (buffer[0] << 8) | buffer[1];
}
bool MS56xx::busCommand(uint8_t command)
{
this->device_->beginTransmission();
this->device_->transfer(command);
this->device_->endTransmission();
return true;
}
uint32_t MS56xx::osrDelay() {
// Delay times taken from:
// https://www.amsys-sensor.com/downloads/notes/MS5XXX-C-code-example-for-MS56xx-MS57xx-MS58xx-AMSYS-an520e.pdf
switch (osr_) {
case _256:
return 600;
case _512:
return 1200;
case _1024:
return 2300;
case _2048:
return 4600;
case _4096:
return 9100;
default:
STA_UNREACHABLE();
}
}
bool MS56xx::busRead(uint8_t reg, uint8_t * buffer, size_t length)
{
this->device_->beginTransmission();
this->device_->transfer(reg);
this->device_->receive(buffer, length);
this->device_->endTransmission();
return true;
}
}