Youen Toupin
3 years ago
21 changed files with 2795 additions and 0 deletions
@ -0,0 +1,33 @@ |
|||||||
|
# License Summary for Repository |
||||||
|
``` |
||||||
|
Important Notice: |
||||||
|
Changes, suggestions and commits in this repository may only be done putting them |
||||||
|
under the same license of the respective file. |
||||||
|
All rights of the respective copyright holders shall be reserved. |
||||||
|
Brands and product names are trademarks of their respective owners. |
||||||
|
Referred and linked files/pages are out-of-scope of this repository and underly |
||||||
|
their respective licenses. |
||||||
|
``` |
||||||
|
## License |
||||||
|
|
||||||
|
Copyright (c) 2018 Infineon Technologies AG |
||||||
|
|
||||||
|
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the |
||||||
|
following conditions are met: |
||||||
|
|
||||||
|
Redistributions of source code must retain the above copyright notice, this list of conditions and the following |
||||||
|
disclaimer. |
||||||
|
|
||||||
|
Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following |
||||||
|
disclaimer in the documentation and/or other materials provided with the distribution. |
||||||
|
|
||||||
|
Neither the name of the copyright holders nor the names of its contributors may be used to endorse or promote |
||||||
|
products derived from this software without specific prior written permission. |
||||||
|
|
||||||
|
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, |
||||||
|
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE |
||||||
|
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, |
||||||
|
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR |
||||||
|
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, |
||||||
|
WHETHER IN CONTRACT, STRICT LIABILITY,OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE |
||||||
|
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. |
@ -0,0 +1,70 @@ |
|||||||
|
# DPS310-Digital-Pressure-Sensor |
||||||
|
|
||||||
|
[![Build Status](https://travis-ci.org/Infineon/DPS310-Pressure-Sensor.svg?branch=master)](https://travis-ci.org/Infineon/DPS310-Pressure-Sensor) |
||||||
|
|
||||||
|
<img src="https://github.com/Infineon/Assets/blob/master/Pictures/DPS310_PP.jpg" width=150><img src="https://github.com/Infineon/Assets/blob/master/Pictures/DPS310-Pressure-Shield2Go_Top.png" width=300> |
||||||
|
|
||||||
|
Library of Infineon's highly sensitive [DPS310 sensor](https://www.infineon.com/cms/de/product/sensor/capacitive-pressure-sensor-for-consumer-applications/DPS310/productType.html?productType=5546d462525dbac4015312b96a743801) for Arduino. |
||||||
|
|
||||||
|
## Summary |
||||||
|
|
||||||
|
The [DPS310](https://www.infineon.com/dgdl/Infineon-DPS310-DS-v01_00-EN.pdf?fileId=5546d462576f34750157750826c42242) is a miniaturized digital barometric air pressure sensor with a high accuracy and a low current consumption, capable of measuring both pressure and temperature. The internal signal processor converts the output from the pressure and temperature sensor elements to 24 bit results. Each unit is individually calibrated, the calibration coefficients calculated during this process are stored in the calibration registers. The available raw data of the sensor can be calibrated by using the pre-calibrated coefficients as they are used in the application to convert the measurement results to high accuracy pressure and temperature values. |
||||||
|
|
||||||
|
Sensor measurements and calibration coefficients are available through the serial I2C or SPI interface. |
||||||
|
|
||||||
|
## Key Features and Applications |
||||||
|
* Supply voltage range 1.7V to 3.6V |
||||||
|
* Operation range 300hPa – 1200hPa |
||||||
|
* Sensor’s precision 0.005hPa |
||||||
|
* Relative accuracy ±0.06hPa |
||||||
|
* Pressure temperature sensitivity of 0.5Pa/K |
||||||
|
* Temperature accuracy ±0.5C° |
||||||
|
* Applications |
||||||
|
* Wearable applications, sport and fitness activities tracking |
||||||
|
* Drones automatic pilot, fix point flying |
||||||
|
* Indoor navigation, altitude metering |
||||||
|
|
||||||
|
## Installation |
||||||
|
|
||||||
|
### Integration of Library |
||||||
|
|
||||||
|
Please download this repository from GitHub by clicking on the following field in the latest [release](https://github.com/Infineon/DPS310-Pressure-Sensor/releases) of this repository: |
||||||
|
|
||||||
|
![Download Library](https://raw.githubusercontent.com/infineon/assets/master/Pictures/Releases_Generic.jpg) |
||||||
|
|
||||||
|
To install the DPS310 pressure sensor library in the Arduino IDE, please go now to **Sketch** > **Include Library** > **Add .ZIP Library...** in the Arduino IDE and navigate to the downloaded .ZIP file of this repository. The library will be installed in your Arduino sketch folder in libraries and you can select as well as include this one to your project under **Sketch** > **Include Library** > **DPS310**. |
||||||
|
|
||||||
|
![Install Library](https://raw.githubusercontent.com/infineon/assets/master/Pictures/Library_Install_ZIP.png) |
||||||
|
|
||||||
|
## Usage |
||||||
|
Please see the example sketches in the `/examples` directory in this library to learn more about the usage of the library. Especially, take care of the respective SPI and I²C configuration of the sensor. |
||||||
|
For more information, please consult the datasheet [here](https://www.infineon.com/dgdl/Infineon-DPS310-DS-v01_00-EN.pdf?fileId=5546d462576f34750157750826c42242). |
||||||
|
|
||||||
|
Currently, there exists the DPS310 Pressure Shield2Go evaluation board as a break out board: |
||||||
|
|
||||||
|
* [DPS310 Pressure Shield2Go](https://www.infineon.com/cms/de/product/evaluation-boards/s2go-pressure-dps310/) |
||||||
|
|
||||||
|
### DPS310 Pressure Shield2Go |
||||||
|
The DPS310 Pressure Shield2Go is a standalone break out board with Infineon's Shield2Go formfactor and pin out. You can connect it easily to any microcontroller of your choice which is Arduino compatible and has 3.3 V logic level (please note that the Arduino UNO has 5 V logic level and cannot be used without level shifting). |
||||||
|
Please consult the [wiki](https://github.com/Infineon/DPS310-Pressure-Sensor/wiki) for additional details about the board. |
||||||
|
|
||||||
|
Each sensor can only work either SPI or I2C. To convert from SPI to I2C, for example, you have to re-solder the resistors on the Shield2Go. Please take care that every Shield2Go for the DPS310 is shipped as I2C configuration right now. |
||||||
|
|
||||||
|
* [Link](https://github.com/Infineon/DPS310-Pressure-Sensor/wiki) to the wiki with more information |
||||||
|
|
||||||
|
However, every Shield2Go is directly compatible with Infineon's XMC2Go and the recommended quick start is to use an XMC2Go for evaluation. Therefore, please install (if not already done) also the [XMC-for-Arduino](https://github.com/Infineon/XMC-for-Arduino) implementation and choose afterwards **XMC1100 XMC2Go** from the **Tools**>**Board** menu in the Arduino IDE if working with this evaluation board. To use it, please plug the DPS310 Pressure Shield2Go onto the XMC2Go as shown below. |
||||||
|
|
||||||
|
<img src="https://github.com/Infineon/Assets/blob/master/Pictures/DPS310_S2Go_w_XMC2Go.png" width=250> |
||||||
|
|
||||||
|
## Known Issues |
||||||
|
|
||||||
|
### Temperature Measurement Issue |
||||||
|
There could be a problem with temperature measurement of the DPS310. If your DPS310 indicates a temperature around 60 °C although you expect around room temperature, e.g. 20 °C, please call the function correctTemp() as included in the library to fix this issue. |
||||||
|
|
||||||
|
In case you need additional help, please do not hesitate to open an issue in this repository. |
||||||
|
|
||||||
|
### Interrupt mode |
||||||
|
Interrupt mode not working reliably on XMC2Go for DPS310 right now. |
||||||
|
|
||||||
|
### Additional Information |
||||||
|
Please find the datasheet of the DPS310 [here](https://www.infineon.com/dgdl/Infineon-DPS310-DS-v01_00-EN.pdf?fileId=5546d462576f34750157750826c42242). It depends on the evaluation board which you are using or the respective configuration of the sensor on your PCB which communication protocol as well as addresses you need to use for communicating with the sensor. |
@ -0,0 +1,98 @@ |
|||||||
|
#include <Dps310.h> |
||||||
|
|
||||||
|
// Dps310 Opject
|
||||||
|
Dps310 Dps310PressureSensor = Dps310(); |
||||||
|
|
||||||
|
void setup() |
||||||
|
{ |
||||||
|
Serial.begin(9600); |
||||||
|
while (!Serial); |
||||||
|
|
||||||
|
//Call begin to initialize Dps310PressureSensor
|
||||||
|
//The parameter 0x76 is the bus address. The default address is 0x77 and does not need to be given.
|
||||||
|
//Dps310PressureSensor.begin(Wire, 0x76);
|
||||||
|
//Use the commented line below instead to use the default I2C address.
|
||||||
|
Dps310PressureSensor.begin(Wire); |
||||||
|
|
||||||
|
//temperature measure rate (value from 0 to 7)
|
||||||
|
//2^temp_mr temperature measurement results per second
|
||||||
|
int16_t temp_mr = 2; |
||||||
|
//temperature oversampling rate (value from 0 to 7)
|
||||||
|
//2^temp_osr internal temperature measurements per result
|
||||||
|
//A higher value increases precision
|
||||||
|
int16_t temp_osr = 2; |
||||||
|
//pressure measure rate (value from 0 to 7)
|
||||||
|
//2^prs_mr pressure measurement results per second
|
||||||
|
int16_t prs_mr = 2; |
||||||
|
//pressure oversampling rate (value from 0 to 7)
|
||||||
|
//2^prs_osr internal pressure measurements per result
|
||||||
|
//A higher value increases precision
|
||||||
|
int16_t prs_osr = 2; |
||||||
|
//startMeasureBothCont enables background mode
|
||||||
|
//temperature and pressure ar measured automatically
|
||||||
|
//High precision and hgh measure rates at the same time are not available.
|
||||||
|
//Consult Datasheet (or trial and error) for more information
|
||||||
|
int16_t ret = Dps310PressureSensor.startMeasureBothCont(temp_mr, temp_osr, prs_mr, prs_osr); |
||||||
|
//Use one of the commented lines below instead to measure only temperature or pressure
|
||||||
|
//int16_t ret = Dps310PressureSensor.startMeasureTempCont(temp_mr, temp_osr);
|
||||||
|
//int16_t ret = Dps310PressureSensor.startMeasurePressureCont(prs_mr, prs_osr);
|
||||||
|
|
||||||
|
|
||||||
|
if (ret != 0) |
||||||
|
{ |
||||||
|
Serial.print("Init FAILED! ret = "); |
||||||
|
Serial.println(ret); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
Serial.println("Init complete!"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void loop() |
||||||
|
{ |
||||||
|
uint8_t pressureCount = 20; |
||||||
|
float pressure[pressureCount]; |
||||||
|
uint8_t temperatureCount = 20; |
||||||
|
float temperature[temperatureCount]; |
||||||
|
|
||||||
|
//This function writes the results of continuous measurements to the arrays given as parameters
|
||||||
|
//The parameters temperatureCount and pressureCount should hold the sizes of the arrays temperature and pressure when the function is called
|
||||||
|
//After the end of the function, temperatureCount and pressureCount hold the numbers of values written to the arrays
|
||||||
|
//Note: The Dps310 cannot save more than 32 results. When its result buffer is full, it won't save any new measurement results
|
||||||
|
int16_t ret = Dps310PressureSensor.getContResults(temperature, temperatureCount, pressure, pressureCount); |
||||||
|
|
||||||
|
if (ret != 0) |
||||||
|
{ |
||||||
|
Serial.println(); |
||||||
|
Serial.println(); |
||||||
|
Serial.print("FAIL! ret = "); |
||||||
|
Serial.println(ret); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
Serial.println(); |
||||||
|
Serial.println(); |
||||||
|
Serial.print(temperatureCount); |
||||||
|
Serial.println(" temperature values found: "); |
||||||
|
for (int16_t i = 0; i < temperatureCount; i++) |
||||||
|
{ |
||||||
|
Serial.print(temperature[i]); |
||||||
|
Serial.println(" degrees of Celsius"); |
||||||
|
} |
||||||
|
|
||||||
|
Serial.println(); |
||||||
|
Serial.print(pressureCount); |
||||||
|
Serial.println(" pressure values found: "); |
||||||
|
for (int16_t i = 0; i < pressureCount; i++) |
||||||
|
{ |
||||||
|
Serial.print(pressure[i]); |
||||||
|
Serial.println(" Pascal"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
//Wait some time, so that the Dps310 can refill its buffer
|
||||||
|
delay(10000); |
||||||
|
} |
@ -0,0 +1,74 @@ |
|||||||
|
#include <Dps310.h> |
||||||
|
|
||||||
|
// Dps310 Opject
|
||||||
|
Dps310 Dps310PressureSensor = Dps310(); |
||||||
|
|
||||||
|
void setup() |
||||||
|
{ |
||||||
|
Serial.begin(9600); |
||||||
|
while (!Serial); |
||||||
|
|
||||||
|
|
||||||
|
//Call begin to initialize Dps310PressureSensor
|
||||||
|
//The parameter 0x76 is the bus address. The default address is 0x77 and does not need to be given.
|
||||||
|
//Dps310PressureSensor.begin(Wire, 0x76);
|
||||||
|
//Use the commented line below instead of the one above to use the default I2C address.
|
||||||
|
//if you are using the Pressure 3 click Board, you need 0x76
|
||||||
|
Dps310PressureSensor.begin(Wire); |
||||||
|
|
||||||
|
Serial.println("Init complete!"); |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void loop() |
||||||
|
{ |
||||||
|
float temperature; |
||||||
|
float pressure; |
||||||
|
uint8_t oversampling = 7; |
||||||
|
int16_t ret; |
||||||
|
Serial.println(); |
||||||
|
|
||||||
|
//lets the Dps310 perform a Single temperature measurement with the last (or standard) configuration
|
||||||
|
//The result will be written to the paramerter temperature
|
||||||
|
//ret = Dps310PressureSensor.measureTempOnce(temperature);
|
||||||
|
//the commented line below does exactly the same as the one above, but you can also config the precision
|
||||||
|
//oversampling can be a value from 0 to 7
|
||||||
|
//the Dps 310 will perform 2^oversampling internal temperature measurements and combine them to one result with higher precision
|
||||||
|
//measurements with higher precision take more time, consult datasheet for more information
|
||||||
|
ret = Dps310PressureSensor.measureTempOnce(temperature, oversampling); |
||||||
|
|
||||||
|
if (ret != 0) |
||||||
|
{ |
||||||
|
//Something went wrong.
|
||||||
|
//Look at the library code for more information about return codes
|
||||||
|
Serial.print("FAIL! ret = "); |
||||||
|
Serial.println(ret); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
Serial.print("Temperature: "); |
||||||
|
Serial.print(temperature); |
||||||
|
Serial.println(" degrees of Celsius"); |
||||||
|
} |
||||||
|
|
||||||
|
//Pressure measurement behaves like temperature measurement
|
||||||
|
//ret = Dps310PressureSensor.measurePressureOnce(pressure);
|
||||||
|
ret = Dps310PressureSensor.measurePressureOnce(pressure, oversampling); |
||||||
|
if (ret != 0) |
||||||
|
{ |
||||||
|
//Something went wrong.
|
||||||
|
//Look at the library code for more information about return codes
|
||||||
|
Serial.print("FAIL! ret = "); |
||||||
|
Serial.println(ret); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
Serial.print("Pressure: "); |
||||||
|
Serial.print(pressure); |
||||||
|
Serial.println(" Pascal"); |
||||||
|
} |
||||||
|
|
||||||
|
//Wait some time
|
||||||
|
delay(500); |
||||||
|
} |
@ -0,0 +1,112 @@ |
|||||||
|
#include <Dps310.h> |
||||||
|
|
||||||
|
// Dps310 Opject
|
||||||
|
Dps310 Dps310PressureSensor = Dps310(); |
||||||
|
|
||||||
|
void onFifoFull(); |
||||||
|
|
||||||
|
const unsigned char pressureLength = 50; |
||||||
|
unsigned char pressureCount = 0; |
||||||
|
float pressure[pressureLength]; |
||||||
|
unsigned char temperatureCount = 0; |
||||||
|
const unsigned char temperatureLength = 50; |
||||||
|
float temperature[temperatureLength]; |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void setup() |
||||||
|
{ |
||||||
|
Serial.begin(9600); |
||||||
|
while (!Serial); |
||||||
|
|
||||||
|
//Call begin to initialize Dps310PressureSensor
|
||||||
|
//The parameter 0x76 is the bus address. The default address is 0x77 and does not need to be given.
|
||||||
|
//Dps310PressureSensor.begin(Wire, 0x76);
|
||||||
|
//Use the commented line below instead to use the default I2C address.
|
||||||
|
Dps310PressureSensor.begin(Wire); |
||||||
|
|
||||||
|
//int16_t ret = Dps310PressureSensor.setInterruptPolarity(1);
|
||||||
|
int16_t ret = Dps310PressureSensor.setInterruptSources(1, 0); |
||||||
|
//clear interrupt flag by reading
|
||||||
|
Dps310PressureSensor.getIntStatusFifoFull(); |
||||||
|
|
||||||
|
//initialization of Interrupt for Controller unit
|
||||||
|
//SDO pin of Dps310 has to be connected with interrupt pin
|
||||||
|
int16_t interruptPin = 3; |
||||||
|
pinMode(interruptPin, INPUT); |
||||||
|
attachInterrupt(digitalPinToInterrupt(interruptPin), onFifoFull, RISING); |
||||||
|
|
||||||
|
//start of a continuous measurement just like before
|
||||||
|
int16_t temp_mr = 3; |
||||||
|
int16_t temp_osr = 2; |
||||||
|
int16_t prs_mr = 1; |
||||||
|
int16_t prs_osr = 3; |
||||||
|
ret = Dps310PressureSensor.startMeasureBothCont(temp_mr, temp_osr, prs_mr, prs_osr); |
||||||
|
if (ret != 0) |
||||||
|
{ |
||||||
|
Serial.print("Init FAILED! ret = "); |
||||||
|
Serial.println(ret); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
Serial.println("Init complete!"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
void loop() |
||||||
|
{ |
||||||
|
//do other stuff
|
||||||
|
Serial.println("loop running"); |
||||||
|
delay(500); |
||||||
|
|
||||||
|
|
||||||
|
//if result arrays are full
|
||||||
|
//This could also be in the interrupt handler, but it would take too much time for a proper ISR
|
||||||
|
if (pressureCount == pressureLength && temperatureCount == temperatureLength) |
||||||
|
{ |
||||||
|
//print results
|
||||||
|
Serial.println(); |
||||||
|
Serial.println(); |
||||||
|
Serial.print(temperatureCount); |
||||||
|
Serial.println(" temperature values found: "); |
||||||
|
for (int16_t i = 0; i < temperatureCount; i++) |
||||||
|
{ |
||||||
|
Serial.print(temperature[i]); |
||||||
|
Serial.println(" degrees of Celsius"); |
||||||
|
} |
||||||
|
Serial.println(); |
||||||
|
Serial.print(pressureCount); |
||||||
|
Serial.println(" pressure values found: "); |
||||||
|
for (int16_t i = 0; i < pressureCount; i++) |
||||||
|
{ |
||||||
|
Serial.print(pressure[i]); |
||||||
|
Serial.println(" Pascal"); |
||||||
|
} |
||||||
|
Serial.println(); |
||||||
|
Serial.println(); |
||||||
|
//reset result counters
|
||||||
|
pressureCount = 0; |
||||||
|
temperatureCount = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
//interrupt handler
|
||||||
|
void onFifoFull() |
||||||
|
{ |
||||||
|
//message for debugging
|
||||||
|
Serial.println("Interrupt handler called"); |
||||||
|
|
||||||
|
//clear interrupt flag by reading
|
||||||
|
Dps310PressureSensor.getIntStatusFifoFull(); |
||||||
|
|
||||||
|
//calculate the number of free indexes in the result arrays
|
||||||
|
uint8_t prs_freespace = pressureLength - pressureCount; |
||||||
|
uint8_t temp_freespace = temperatureLength - temperatureCount; |
||||||
|
//read the results from Dps310, new results will be added at the end of the arrays
|
||||||
|
Dps310PressureSensor.getContResults(&temperature[temperatureCount], temp_freespace, &pressure[pressureCount], prs_freespace); |
||||||
|
//after reading the result counters are increased by the amount of new results
|
||||||
|
pressureCount += prs_freespace; |
||||||
|
temperatureCount += temp_freespace; |
||||||
|
} |
@ -0,0 +1,103 @@ |
|||||||
|
#include <Dps310.h> |
||||||
|
|
||||||
|
// Dps310 Opject
|
||||||
|
Dps310 Dps310PressureSensor = Dps310(); |
||||||
|
|
||||||
|
void setup() |
||||||
|
{ |
||||||
|
//pin number of your slave select line
|
||||||
|
//XMC2GO
|
||||||
|
int16_t pin_cs = 3; |
||||||
|
//for XMC 1100 Bootkit & XMC4700 Relax Kit uncomment the following line
|
||||||
|
//int16_t pin_cs = 10;
|
||||||
|
|
||||||
|
Serial.begin(9600); |
||||||
|
while (!Serial); |
||||||
|
|
||||||
|
|
||||||
|
//Call begin to initialize Dps310
|
||||||
|
//The parameter pin_nr is the number of the CS pin on your Microcontroller
|
||||||
|
Dps310PressureSensor.begin(SPI, pin_cs); |
||||||
|
|
||||||
|
//temperature measure rate (value from 0 to 7)
|
||||||
|
//2^temp_mr temperature measurement results per second
|
||||||
|
int16_t temp_mr = 2; |
||||||
|
//temperature oversampling rate (value from 0 to 7)
|
||||||
|
//2^temp_osr internal temperature measurements per result
|
||||||
|
//A higher value increases precision
|
||||||
|
int16_t temp_osr = 2; |
||||||
|
//pressure measure rate (value from 0 to 7)
|
||||||
|
//2^prs_mr pressure measurement results per second
|
||||||
|
int16_t prs_mr = 2; |
||||||
|
//pressure oversampling rate (value from 0 to 7)
|
||||||
|
//2^prs_osr internal pressure measurements per result
|
||||||
|
//A higher value increases precision
|
||||||
|
int16_t prs_osr = 2; |
||||||
|
//startMeasureBothCont enables background mode
|
||||||
|
//temperature and pressure ar measured automatically
|
||||||
|
//High precision and hgh measure rates at the same time are not available.
|
||||||
|
//Consult Datasheet (or trial and error) for more information
|
||||||
|
int16_t ret = Dps310PressureSensor.startMeasureBothCont(temp_mr, temp_osr, prs_mr, prs_osr); |
||||||
|
//Use one of the commented lines below instead to measure only temperature or pressure
|
||||||
|
//int16_t ret = Dps310PressureSensor.startMeasureTempCont(temp_mr, temp_osr);
|
||||||
|
//int16_t ret = Dps310PressureSensor.startMeasurePressureCont(prs_mr, prs_osr);
|
||||||
|
|
||||||
|
|
||||||
|
if (ret != 0) |
||||||
|
{ |
||||||
|
Serial.print("Init FAILED! ret = "); |
||||||
|
Serial.println(ret); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
Serial.println("Init complete!"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void loop() |
||||||
|
{ |
||||||
|
uint8_t pressureCount = 20; |
||||||
|
float pressure[pressureCount]; |
||||||
|
uint8_t temperatureCount = 20; |
||||||
|
float temperature[temperatureCount]; |
||||||
|
|
||||||
|
//This function writes the results of continuous measurements to the arrays given as parameters
|
||||||
|
//The parameters temperatureCount and pressureCount should hold the sizes of the arrays temperature and pressure when the function is called
|
||||||
|
//After the end of the function, temperatureCount and pressureCount hold the numbers of values written to the arrays
|
||||||
|
//Note: The Dps310 cannot save more than 32 results. When its result buffer is full, it won't save any new measurement results
|
||||||
|
int16_t ret = Dps310PressureSensor.getContResults(temperature, temperatureCount, pressure, pressureCount); |
||||||
|
|
||||||
|
if (ret != 0) |
||||||
|
{ |
||||||
|
Serial.println(); |
||||||
|
Serial.println(); |
||||||
|
Serial.print("FAIL! ret = "); |
||||||
|
Serial.println(ret); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
Serial.println(); |
||||||
|
Serial.println(); |
||||||
|
Serial.print(temperatureCount); |
||||||
|
Serial.println(" temperature values found: "); |
||||||
|
for (int16_t i = 0; i < temperatureCount; i++) |
||||||
|
{ |
||||||
|
Serial.print(temperature[i]); |
||||||
|
Serial.println(" degrees of Celsius"); |
||||||
|
} |
||||||
|
|
||||||
|
Serial.println(); |
||||||
|
Serial.print(pressureCount); |
||||||
|
Serial.println(" pressure values found: "); |
||||||
|
for (int16_t i = 0; i < pressureCount; i++) |
||||||
|
{ |
||||||
|
Serial.print(pressure[i]); |
||||||
|
Serial.println(" Pascal"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
//Wait some time, so that the Dps310 can refill its buffer
|
||||||
|
delay(10000); |
||||||
|
} |
@ -0,0 +1,77 @@ |
|||||||
|
#include <Dps310.h> |
||||||
|
|
||||||
|
// Dps310 Opject
|
||||||
|
Dps310 Dps310PressureSensor = Dps310(); |
||||||
|
|
||||||
|
void setup() |
||||||
|
{ |
||||||
|
//pin number of your slave select line
|
||||||
|
//XMC2GO
|
||||||
|
int16_t pin_cs = 3; |
||||||
|
//for XMC 1100 Bootkit & XMC4700 Relax Kit uncomment the following line
|
||||||
|
//int16_t pin_cs = 10;
|
||||||
|
|
||||||
|
Serial.begin(9600); |
||||||
|
while (!Serial); |
||||||
|
|
||||||
|
|
||||||
|
//Call begin to initialize Dps310PressureSensor
|
||||||
|
//The parameter pin_nr is the number of the CS pin on your Microcontroller
|
||||||
|
Dps310PressureSensor.begin(SPI, pin_cs); |
||||||
|
|
||||||
|
Serial.println("Init complete!"); |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void loop() |
||||||
|
{ |
||||||
|
float temperature; |
||||||
|
float pressure; |
||||||
|
uint8_t oversampling = 7; |
||||||
|
int16_t ret; |
||||||
|
Serial.println(); |
||||||
|
|
||||||
|
//lets the Dps310 perform a Single temperature measurement with the last (or standard) configuration
|
||||||
|
//The result will be written to the paramerter temperature
|
||||||
|
//ret = Dps310PressureSensor.measureTempOnce(temperature);
|
||||||
|
//the commented line below does exactly the same as the one above, but you can also config the precision
|
||||||
|
//oversampling can be a value from 0 to 7
|
||||||
|
//the Dps 310 will perform 2^oversampling internal temperature measurements and combine them to one result with higher precision
|
||||||
|
//measurements with higher precision take more time, consult datasheet for more information
|
||||||
|
ret = Dps310PressureSensor.measureTempOnce(temperature, oversampling); |
||||||
|
|
||||||
|
if (ret != 0) |
||||||
|
{ |
||||||
|
//Something went wrong.
|
||||||
|
//Look at the library code for more information about return codes
|
||||||
|
Serial.print("FAIL! ret = "); |
||||||
|
Serial.println(ret); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
Serial.print("Temperature: "); |
||||||
|
Serial.print(temperature); |
||||||
|
Serial.println(" degrees of Celsius"); |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
//ret = Dps310PressureSensor.measurePressureOnce(pressure);
|
||||||
|
ret = Dps310PressureSensor.measurePressureOnce(pressure, oversampling); |
||||||
|
if (ret != 0) |
||||||
|
{ |
||||||
|
//Something went wrong.
|
||||||
|
//Look at the library code for more information about return codes
|
||||||
|
Serial.print("FAIL! ret = "); |
||||||
|
Serial.println(ret); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
Serial.print("Pressure: "); |
||||||
|
Serial.print(pressure); |
||||||
|
Serial.println(" Pascal"); |
||||||
|
} |
||||||
|
|
||||||
|
//Wait some time
|
||||||
|
delay(1000); |
||||||
|
} |
@ -0,0 +1,130 @@ |
|||||||
|
#include <Dps310.h> |
||||||
|
|
||||||
|
// Dps310 Opject
|
||||||
|
Dps310 Dps310PressureSensor = Dps310(); |
||||||
|
|
||||||
|
void onFifoFull(); |
||||||
|
|
||||||
|
const unsigned char pressureLength = 50; |
||||||
|
unsigned char pressureCount = 0; |
||||||
|
float pressure[pressureLength]; |
||||||
|
unsigned char temperatureCount = 0; |
||||||
|
const unsigned char temperatureLength = 50; |
||||||
|
float temperature[temperatureLength]; |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void setup() |
||||||
|
{ |
||||||
|
//pin number of your slave select line
|
||||||
|
//XMC2GO
|
||||||
|
int16_t pin_cs = 3; |
||||||
|
//for XMC 1100 Bootkit & XMC4700 Relax Kit uncomment the following line
|
||||||
|
//int16_t pin_cs = 10;
|
||||||
|
|
||||||
|
Serial.begin(9600); |
||||||
|
while (!Serial); |
||||||
|
|
||||||
|
//Call begin to initialize Dps310PressureSensor
|
||||||
|
//The third parameter has to be 1 and enables 3-wire SPI interface
|
||||||
|
//This is necessary, because SDO will be used to indicate interrupts
|
||||||
|
//ATTENTION: Make sure you have connected your MISO and MOSI pins right!
|
||||||
|
// There may NEVER be a direct Connection between MOSI and SDI when 3-wire SPI is enabled
|
||||||
|
// Otherwise, you will cause shortcuts and seriously damage your equipment.
|
||||||
|
// For three wire interface, MISO has to be connected to SDI and there hase to be a resistor between MISO and MOSI
|
||||||
|
// I successfully tested this with a resistor of 1k, but I won't give you any warranty that this works for your equipment too
|
||||||
|
Dps310PressureSensor.begin(SPI, pin_cs, 1); |
||||||
|
|
||||||
|
//config Dps310 for Interrupts
|
||||||
|
// int16_t ret = Dps310PressureSensor.setInterruptPolarity(1);
|
||||||
|
int16_t ret = Dps310PressureSensor.setInterruptSources(1, 0); |
||||||
|
//clear interrupt flag by reading
|
||||||
|
Dps310PressureSensor.getIntStatusFifoFull(); |
||||||
|
|
||||||
|
//initialization of Interrupt for Controller unit
|
||||||
|
//SDO pin of Dps310 has to be connected with interrupt pin
|
||||||
|
int16_t interruptPin = 2; |
||||||
|
pinMode(interruptPin, INPUT); |
||||||
|
Serial.println(digitalPinToInterrupt(interruptPin)); |
||||||
|
attachInterrupt(digitalPinToInterrupt(interruptPin), onFifoFull, RISING); |
||||||
|
|
||||||
|
//start of a continuous measurement just like before
|
||||||
|
int16_t temp_mr = 3; |
||||||
|
int16_t temp_osr = 2; |
||||||
|
int16_t prs_mr = 1; |
||||||
|
int16_t prs_osr = 3; |
||||||
|
ret = Dps310PressureSensor.startMeasureBothCont(temp_mr, temp_osr, prs_mr, prs_osr); |
||||||
|
if (ret != 0) |
||||||
|
{ |
||||||
|
Serial.print("Init FAILED! ret = "); |
||||||
|
Serial.println(ret); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
Serial.println("Init complete!"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
void loop() |
||||||
|
{ |
||||||
|
|
||||||
|
//do other stuff
|
||||||
|
Serial.println("loop running"); |
||||||
|
delay(500); |
||||||
|
|
||||||
|
|
||||||
|
//if result arrays are full
|
||||||
|
//This could also be in the interrupt handler, but it would take too much time for an interrupt
|
||||||
|
if (pressureCount == pressureLength && temperatureCount == temperatureLength) |
||||||
|
{ |
||||||
|
//print results
|
||||||
|
Serial.println(); |
||||||
|
Serial.println(); |
||||||
|
Serial.print(temperatureCount); |
||||||
|
Serial.println(" temperature values found: "); |
||||||
|
for (int16_t i = 0; i < temperatureCount; i++) |
||||||
|
{ |
||||||
|
Serial.print(temperature[i]); |
||||||
|
Serial.println(" degrees of Celsius"); |
||||||
|
} |
||||||
|
|
||||||
|
Serial.println(); |
||||||
|
Serial.print(pressureCount); |
||||||
|
Serial.println(" pressure values found: "); |
||||||
|
for (int16_t i = 0; i < pressureCount; i++) |
||||||
|
{ |
||||||
|
Serial.print(pressure[i]); |
||||||
|
Serial.println(" Pascal"); |
||||||
|
} |
||||||
|
Serial.println(); |
||||||
|
Serial.println(); |
||||||
|
|
||||||
|
//reset result counters
|
||||||
|
pressureCount = 0; |
||||||
|
temperatureCount = 0; |
||||||
|
} |
||||||
|
|
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
void onFifoFull() |
||||||
|
{ |
||||||
|
//message for debugging
|
||||||
|
Serial.println("Interrupt handler called"); |
||||||
|
|
||||||
|
//clear interrupt flag by reading
|
||||||
|
Dps310PressureSensor.getIntStatusFifoFull(); |
||||||
|
|
||||||
|
//calculate the number of free indexes in the result arrays
|
||||||
|
uint8_t prs_freespace = pressureLength - pressureCount; |
||||||
|
uint8_t temp_freespace = temperatureLength - temperatureCount; |
||||||
|
//read the results from Dps310, new results will be added at the end of the arrays
|
||||||
|
Dps310PressureSensor.getContResults(&temperature[temperatureCount], temp_freespace, &pressure[pressureCount], prs_freespace); |
||||||
|
//after reading the result counters are increased by the amount of new results
|
||||||
|
pressureCount += prs_freespace; |
||||||
|
temperatureCount += temp_freespace; |
||||||
|
|
||||||
|
|
||||||
|
} |
@ -0,0 +1,44 @@ |
|||||||
|
####################################### |
||||||
|
# Syntax Coloring Map For IFX Dps310 |
||||||
|
####################################### |
||||||
|
|
||||||
|
####################################### |
||||||
|
# Datatypes (KEYWORD1) |
||||||
|
####################################### |
||||||
|
|
||||||
|
####################################### |
||||||
|
# Methods and Functions (KEYWORD2) |
||||||
|
####################################### |
||||||
|
|
||||||
|
begin KEYWORD2 |
||||||
|
end KEYWORD2 |
||||||
|
getProductId KEYWORD2 |
||||||
|
getRevisionId KEYWORD2 |
||||||
|
standby KEYWORD2 |
||||||
|
measureTempOnce KEYWORD2 |
||||||
|
startMeasureTempOnce KEYWORD2 |
||||||
|
measurePressureOnce KEYWORD2 |
||||||
|
startMeasurePressureOnce KEYWORD2 |
||||||
|
getSingleResult KEYWORD2 |
||||||
|
startMeasureTempCont KEYWORD2 |
||||||
|
startMeasurePressureCont KEYWORD2 |
||||||
|
startMeasureBothCont KEYWORD2 |
||||||
|
getContResults KEYWORD2 |
||||||
|
setInterruptPolarity KEYWORD2 |
||||||
|
setInterruptSources KEYWORD2 |
||||||
|
getIntFiofoFull KEYWORD2 |
||||||
|
getIntStatusTempReady KEYWORD2 |
||||||
|
getIntStatusPrsReady KEYWORD2 |
||||||
|
correctTemp KEYWORD2 |
||||||
|
|
||||||
|
|
||||||
|
####################################### |
||||||
|
# Instances (KEYWORD2) |
||||||
|
####################################### |
||||||
|
|
||||||
|
Dps310 KEYWORD2 |
||||||
|
|
||||||
|
####################################### |
||||||
|
# Constants (LITERAL1) |
||||||
|
####################################### |
||||||
|
|
@ -0,0 +1,13 @@ |
|||||||
|
{ |
||||||
|
"name": "Digital-Pressure-Sensor", |
||||||
|
"keywords": "barometric, pressure, temperature, sensor, shield2go", |
||||||
|
"description": "Library of Infineon's highly sensitive DPS310 sensor and DPS422 sensor for Arduino.", |
||||||
|
"repository": |
||||||
|
{ |
||||||
|
"type": "git", |
||||||
|
"url": "https://github.com/Infineon/DPS310-Pressure-Sensor.git" |
||||||
|
}, |
||||||
|
"version": "1.0.6", |
||||||
|
"frameworks": "arduino", |
||||||
|
"platforms": "infineonxmc" |
||||||
|
} |
@ -0,0 +1,9 @@ |
|||||||
|
name=DigitalPressureSensor |
||||||
|
version=1.0.7 |
||||||
|
author=Infineon Technologies |
||||||
|
maintainer=Infineon Technologies <www.infineon.com> |
||||||
|
sentence=This library provides an Interface for Infineon's DPS310 Pressure Sensor. |
||||||
|
paragraph=The DPS series are highly-sensitive pressure sensors (with temperature compensation) that can be connected via SPI or I2C. |
||||||
|
category=Sensors |
||||||
|
url=http://www.infineon.com/cms/de/product/sensor/capacitive-pressure-sensor-for-consumer-applications/DPS310/productType.html?productType=5546d462525dbac4015312b96a743801 |
||||||
|
architectures=* |
@ -0,0 +1,190 @@ |
|||||||
|
#include "Dps310.h" |
||||||
|
|
||||||
|
using namespace dps; |
||||||
|
using namespace dps310; |
||||||
|
|
||||||
|
int16_t Dps310::getContResults(float *tempBuffer, |
||||||
|
uint8_t &tempCount, |
||||||
|
float *prsBuffer, |
||||||
|
uint8_t &prsCount) |
||||||
|
{ |
||||||
|
return DpsClass::getContResults(tempBuffer, tempCount, prsBuffer, prsCount, registers[FIFO_EMPTY]); |
||||||
|
} |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
int16_t Dps310::setInterruptSources(uint8_t intr_source, uint8_t polarity) |
||||||
|
{ |
||||||
|
//Interrupts are not supported with 4 Wire SPI
|
||||||
|
if (!m_SpiI2c & !m_threeWire) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
return writeByteBitfield(intr_source, registers[INT_SEL]) || writeByteBitfield(polarity, registers[INT_HL]); |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
void Dps310::init(void) |
||||||
|
{ |
||||||
|
int16_t prodId = readByteBitfield(registers[PROD_ID]); |
||||||
|
if (prodId < 0) |
||||||
|
{ |
||||||
|
//Connected device is not a Dps310
|
||||||
|
m_initFail = 1U; |
||||||
|
return; |
||||||
|
} |
||||||
|
m_productID = prodId; |
||||||
|
|
||||||
|
int16_t revId = readByteBitfield(registers[REV_ID]); |
||||||
|
if (revId < 0) |
||||||
|
{ |
||||||
|
m_initFail = 1U; |
||||||
|
return; |
||||||
|
} |
||||||
|
m_revisionID = revId; |
||||||
|
|
||||||
|
//find out which temperature sensor is calibrated with coefficients...
|
||||||
|
int16_t sensor = readByteBitfield(registers[TEMP_SENSORREC]); |
||||||
|
if (sensor < 0) |
||||||
|
{ |
||||||
|
m_initFail = 1U; |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
//...and use this sensor for temperature measurement
|
||||||
|
m_tempSensor = sensor; |
||||||
|
if (writeByteBitfield((uint8_t)sensor, registers[TEMP_SENSOR]) < 0) |
||||||
|
{ |
||||||
|
m_initFail = 1U; |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
//read coefficients
|
||||||
|
if (readcoeffs() < 0) |
||||||
|
{ |
||||||
|
m_initFail = 1U; |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
//set to standby for further configuration
|
||||||
|
standby(); |
||||||
|
|
||||||
|
//set measurement precision and rate to standard values;
|
||||||
|
configTemp(DPS__MEASUREMENT_RATE_4, DPS__OVERSAMPLING_RATE_8); |
||||||
|
configPressure(DPS__MEASUREMENT_RATE_4, DPS__OVERSAMPLING_RATE_8); |
||||||
|
|
||||||
|
//perform a first temperature measurement
|
||||||
|
//the most recent temperature will be saved internally
|
||||||
|
//and used for compensation when calculating pressure
|
||||||
|
float trash; |
||||||
|
measureTempOnce(trash); |
||||||
|
|
||||||
|
//make sure the DPS310 is in standby after initialization
|
||||||
|
standby(); |
||||||
|
|
||||||
|
// Fix IC with a fuse bit problem, which lead to a wrong temperature
|
||||||
|
// Should not affect ICs without this problem
|
||||||
|
correctTemp(); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t Dps310::readcoeffs(void) |
||||||
|
{ |
||||||
|
// TODO: remove magic number
|
||||||
|
uint8_t buffer[18]; |
||||||
|
//read COEF registers to buffer
|
||||||
|
int16_t ret = readBlock(coeffBlock, buffer); |
||||||
|
|
||||||
|
//compose coefficients from buffer content
|
||||||
|
m_c0Half = ((uint32_t)buffer[0] << 4) | (((uint32_t)buffer[1] >> 4) & 0x0F); |
||||||
|
getTwosComplement(&m_c0Half, 12); |
||||||
|
//c0 is only used as c0*0.5, so c0_half is calculated immediately
|
||||||
|
m_c0Half = m_c0Half / 2U; |
||||||
|
|
||||||
|
//now do the same thing for all other coefficients
|
||||||
|
m_c1 = (((uint32_t)buffer[1] & 0x0F) << 8) | (uint32_t)buffer[2]; |
||||||
|
getTwosComplement(&m_c1, 12); |
||||||
|
m_c00 = ((uint32_t)buffer[3] << 12) | ((uint32_t)buffer[4] << 4) | (((uint32_t)buffer[5] >> 4) & 0x0F); |
||||||
|
getTwosComplement(&m_c00, 20); |
||||||
|
m_c10 = (((uint32_t)buffer[5] & 0x0F) << 16) | ((uint32_t)buffer[6] << 8) | (uint32_t)buffer[7]; |
||||||
|
getTwosComplement(&m_c10, 20); |
||||||
|
|
||||||
|
m_c01 = ((uint32_t)buffer[8] << 8) | (uint32_t)buffer[9]; |
||||||
|
getTwosComplement(&m_c01, 16); |
||||||
|
|
||||||
|
m_c11 = ((uint32_t)buffer[10] << 8) | (uint32_t)buffer[11]; |
||||||
|
getTwosComplement(&m_c11, 16); |
||||||
|
m_c20 = ((uint32_t)buffer[12] << 8) | (uint32_t)buffer[13]; |
||||||
|
getTwosComplement(&m_c20, 16); |
||||||
|
m_c21 = ((uint32_t)buffer[14] << 8) | (uint32_t)buffer[15]; |
||||||
|
getTwosComplement(&m_c21, 16); |
||||||
|
m_c30 = ((uint32_t)buffer[16] << 8) | (uint32_t)buffer[17]; |
||||||
|
getTwosComplement(&m_c30, 16); |
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t Dps310::configTemp(uint8_t tempMr, uint8_t tempOsr) |
||||||
|
{ |
||||||
|
int16_t ret = DpsClass::configTemp(tempMr, tempOsr); |
||||||
|
|
||||||
|
writeByteBitfield(m_tempSensor, registers[TEMP_SENSOR]); |
||||||
|
//set TEMP SHIFT ENABLE if oversampling rate higher than eight(2^3)
|
||||||
|
if (tempOsr > DPS310__OSR_SE) |
||||||
|
{ |
||||||
|
ret = writeByteBitfield(1U, registers[TEMP_SE]); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
ret = writeByteBitfield(0U, registers[TEMP_SE]); |
||||||
|
} |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t Dps310::configPressure(uint8_t prsMr, uint8_t prsOsr) |
||||||
|
{ |
||||||
|
int16_t ret = DpsClass::configPressure(prsMr, prsOsr); |
||||||
|
//set PM SHIFT ENABLE if oversampling rate higher than eight(2^3)
|
||||||
|
if (prsOsr > DPS310__OSR_SE) |
||||||
|
{ |
||||||
|
ret = writeByteBitfield(1U, registers[PRS_SE]); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
ret = writeByteBitfield(0U, registers[PRS_SE]); |
||||||
|
} |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
float Dps310::calcTemp(int32_t raw) |
||||||
|
{ |
||||||
|
float temp = raw; |
||||||
|
|
||||||
|
//scale temperature according to scaling table and oversampling
|
||||||
|
temp /= scaling_facts[m_tempOsr]; |
||||||
|
|
||||||
|
//update last measured temperature
|
||||||
|
//it will be used for pressure compensation
|
||||||
|
m_lastTempScal = temp; |
||||||
|
|
||||||
|
//Calculate compensated temperature
|
||||||
|
temp = m_c0Half + m_c1 * temp; |
||||||
|
|
||||||
|
return temp; |
||||||
|
} |
||||||
|
|
||||||
|
float Dps310::calcPressure(int32_t raw) |
||||||
|
{ |
||||||
|
float prs = raw; |
||||||
|
|
||||||
|
//scale pressure according to scaling table and oversampling
|
||||||
|
prs /= scaling_facts[m_prsOsr]; |
||||||
|
|
||||||
|
//Calculate compensated pressure
|
||||||
|
prs = m_c00 + prs * (m_c10 + prs * (m_c20 + prs * m_c30)) + m_lastTempScal * (m_c01 + prs * (m_c11 + prs * m_c21)); |
||||||
|
|
||||||
|
//return pressure
|
||||||
|
return prs; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t Dps310::flushFIFO() |
||||||
|
{ |
||||||
|
return writeByteBitfield(1U, registers[FIFO_FL]); |
||||||
|
} |
@ -0,0 +1,39 @@ |
|||||||
|
#ifndef DPS310_H_INCLUDED |
||||||
|
#define DPS310_H_INCLUDED |
||||||
|
|
||||||
|
#include "DpsClass.h" |
||||||
|
#include "util/dps310_config.h" |
||||||
|
|
||||||
|
class Dps310 : public DpsClass |
||||||
|
{ |
||||||
|
public: |
||||||
|
int16_t getContResults(float *tempBuffer, uint8_t &tempCount, float *prsBuffer, uint8_t &prsCount); |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Set the source of interrupt (FIFO full, measurement values ready) |
||||||
|
*
|
||||||
|
* @param intr_source Interrupt source as defined by Interrupt_source_310_e |
||||||
|
* @param polarity
|
||||||
|
* @return status code
|
||||||
|
*/ |
||||||
|
int16_t setInterruptSources(uint8_t intr_source, uint8_t polarity = 1); |
||||||
|
|
||||||
|
protected: |
||||||
|
uint8_t m_tempSensor; |
||||||
|
|
||||||
|
//compensation coefficients
|
||||||
|
int32_t m_c0Half; |
||||||
|
int32_t m_c1; |
||||||
|
|
||||||
|
/////// implement pure virtual functions ///////
|
||||||
|
|
||||||
|
void init(void); |
||||||
|
int16_t configTemp(uint8_t temp_mr, uint8_t temp_osr); |
||||||
|
int16_t configPressure(uint8_t prs_mr, uint8_t prs_osr); |
||||||
|
int16_t readcoeffs(void); |
||||||
|
int16_t flushFIFO(); |
||||||
|
float calcTemp(int32_t raw); |
||||||
|
float calcPressure(int32_t raw); |
||||||
|
}; |
||||||
|
|
||||||
|
#endif |
@ -0,0 +1,176 @@ |
|||||||
|
#include "Dps422.h" |
||||||
|
|
||||||
|
using namespace dps; |
||||||
|
using namespace dps422; |
||||||
|
|
||||||
|
//////// public /////////
|
||||||
|
|
||||||
|
int16_t Dps422::measureBothOnce(float &prs, float &temp) |
||||||
|
{ |
||||||
|
measureBothOnce(prs, temp, m_prsOsr, m_tempOsr); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t Dps422::measureBothOnce(float &prs, float &temp, uint8_t prs_osr, uint8_t temp_osr) |
||||||
|
{ |
||||||
|
if (prs_osr != m_prsOsr) |
||||||
|
{ |
||||||
|
if (configPressure(0U, prs_osr)) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
if (temp_osr != m_tempOsr) |
||||||
|
{ |
||||||
|
if (configPressure(0U, temp_osr)) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
setOpMode(CMD_BOTH); |
||||||
|
delay(((calcBusyTime(0U, m_tempOsr) + calcBusyTime(0U, m_prsOsr)) / DPS__BUSYTIME_SCALING)); |
||||||
|
// config_registers defined in namespace dps
|
||||||
|
int16_t rdy = readByteBitfield(config_registers[PRS_RDY]) & readByteBitfield(config_registers[TEMP_RDY]); |
||||||
|
switch (rdy) |
||||||
|
{ |
||||||
|
case DPS__FAIL_UNKNOWN: //could not read ready flag
|
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
case 0: //ready flag not set, measurement still in progress
|
||||||
|
standby(); |
||||||
|
return DPS__FAIL_UNFINISHED; |
||||||
|
case 1: //measurement ready, expected case
|
||||||
|
m_opMode = IDLE; |
||||||
|
int32_t raw_temp; |
||||||
|
int32_t raw_psr; |
||||||
|
if (getRawResult(&raw_temp, registerBlocks[TEMP]) || getRawResult(&raw_psr, registerBlocks[PRS])) |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
prs = calcPressure(raw_psr); |
||||||
|
temp = calcTemp(raw_temp); |
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
int16_t Dps422::getContResults(float *tempBuffer, |
||||||
|
uint8_t &tempCount, |
||||||
|
float *prsBuffer, |
||||||
|
uint8_t &prsCount) |
||||||
|
{ |
||||||
|
return DpsClass::getContResults(tempBuffer, tempCount, prsBuffer, prsCount, registers[FIFO_EMPTY]); |
||||||
|
} |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
int16_t Dps422::setInterruptSources(uint8_t intr_source, uint8_t polarity) |
||||||
|
{ |
||||||
|
// Intrrupt only supported by I2C or 3-Wire SPI
|
||||||
|
if (!m_SpiI2c & !m_threeWire) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
|
||||||
|
return writeByteBitfield(intr_source, registers[INTR_SEL]) || writeByteBitfield(polarity, registers[INTR_POL]); |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
//////// private /////////
|
||||||
|
void Dps422::init(void) |
||||||
|
{ |
||||||
|
// m_lastTempScal = 0.08716583251; // in case temperature reading disabled, the default raw temperature value correspond the reference temperature of 27 degress.
|
||||||
|
standby(); |
||||||
|
if (readcoeffs() < 0 || writeByteBitfield(0x01, registers[MUST_SET]) < 0) |
||||||
|
{ |
||||||
|
m_initFail = 1U; |
||||||
|
return; |
||||||
|
} |
||||||
|
configTemp(DPS__MEASUREMENT_RATE_4, DPS__OVERSAMPLING_RATE_8); |
||||||
|
configPressure(DPS__MEASUREMENT_RATE_4, DPS__OVERSAMPLING_RATE_8); |
||||||
|
// get one temperature measurement for pressure compensation
|
||||||
|
float trash; |
||||||
|
measureTempOnce(trash); |
||||||
|
standby(); |
||||||
|
correctTemp(); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t Dps422::readcoeffs(void) |
||||||
|
{ |
||||||
|
uint8_t buffer_temp[3]; |
||||||
|
uint8_t buffer_prs[20]; |
||||||
|
readBlock(coeffBlocks[COEF_TEMP], buffer_temp); |
||||||
|
readBlock(coeffBlocks[COEF_PRS], buffer_prs); |
||||||
|
|
||||||
|
// refer to datasheet
|
||||||
|
// 1. read T_Vbe, T_dVbe and T_gain
|
||||||
|
int32_t t_gain = buffer_temp[0]; // 8 bits
|
||||||
|
int32_t t_dVbe = (uint32_t)buffer_temp[1] >> 1; // 7 bits
|
||||||
|
int32_t t_Vbe = ((uint32_t)buffer_temp[1] & 0x01) | ((uint32_t)buffer_temp[2] << 1); // 9 bits
|
||||||
|
|
||||||
|
getTwosComplement(&t_gain, 8); |
||||||
|
getTwosComplement(&t_dVbe, 7); |
||||||
|
getTwosComplement(&t_Vbe, 9); |
||||||
|
|
||||||
|
// 2. Vbe, dVbe and Aadc
|
||||||
|
float Vbe = t_Vbe * 1.05031e-4 + 0.463232422; |
||||||
|
float dVbe = t_dVbe * 1.25885e-5 + 0.04027621; |
||||||
|
float Aadc = t_gain * 8.4375e-5 + 0.675; |
||||||
|
// 3. Vbe_cal and dVbe_cal
|
||||||
|
float Vbe_cal = Vbe / Aadc; |
||||||
|
float dVbe_cal = dVbe / Aadc; |
||||||
|
// 4. T_calib
|
||||||
|
float T_calib = DPS422_A_0 * dVbe_cal - 273.15; |
||||||
|
// 5. Vbe_cal(T_ref): Vbe value at reference temperature
|
||||||
|
float Vbe_cal_tref = Vbe_cal - (T_calib - DPS422_T_REF) * DPS422_T_C_VBE; |
||||||
|
// 6. alculate PTAT correction coefficient
|
||||||
|
float k_ptat = (DPS422_V_BE_TARGET - Vbe_cal_tref) * DPS422_K_PTAT_CORNER + DPS422_K_PTAT_CURVATURE; |
||||||
|
// 7. calculate A' and B'
|
||||||
|
a_prime = DPS422_A_0 * (Vbe_cal + DPS422_ALPHA * dVbe_cal) * (1 + k_ptat); |
||||||
|
b_prime = -273.15 * (1 + k_ptat) - k_ptat * T_calib; |
||||||
|
|
||||||
|
// c00, c01, c02, c10 : 20 bits
|
||||||
|
// c11, c12: 17 bits
|
||||||
|
// c20: 15 bits; c21: 14 bits; c30 12 bits
|
||||||
|
m_c00 = ((uint32_t)buffer_prs[0] << 12) | ((uint32_t)buffer_prs[1] << 4) | (((uint32_t)buffer_prs[2] & 0xF0) >> 4); |
||||||
|
m_c10 = ((uint32_t)(buffer_prs[2] & 0x0F) << 16) | ((uint32_t)buffer_prs[3] << 8) | (uint32_t)buffer_prs[4]; |
||||||
|
m_c01 = ((uint32_t)buffer_prs[5] << 12) | ((uint32_t)buffer_prs[6] << 4) | (((uint32_t)buffer_prs[7] & 0xF0) >> 4); |
||||||
|
m_c02 = ((uint32_t)(buffer_prs[7] & 0x0F) << 16) | ((uint32_t)buffer_prs[8] << 8) | (uint32_t)buffer_prs[9]; |
||||||
|
m_c20 = ((uint32_t)(buffer_prs[10] & 0x7F) << 8) | (uint32_t)buffer_prs[11]; |
||||||
|
m_c30 = ((uint32_t)(buffer_prs[12] & 0x0F) << 8) | (uint32_t)buffer_prs[13]; |
||||||
|
m_c11 = ((uint32_t)buffer_prs[14] << 9) | ((uint32_t)buffer_prs[15] << 1) | (((uint32_t)buffer_prs[16] & 0x80) >> 7); |
||||||
|
m_c12 = (((uint32_t)buffer_prs[16] & 0x7F) << 10) | ((uint32_t)buffer_prs[17] << 2) | (((uint32_t)buffer_prs[18] & 0xC0) >> 6); |
||||||
|
m_c21 = (((uint32_t)buffer_prs[18] & 0x3F) << 8) | ((uint32_t)buffer_prs[19]); |
||||||
|
|
||||||
|
getTwosComplement(&m_c00, 20); |
||||||
|
getTwosComplement(&m_c01, 20); |
||||||
|
getTwosComplement(&m_c02, 20); |
||||||
|
getTwosComplement(&m_c10, 20); |
||||||
|
getTwosComplement(&m_c11, 17); |
||||||
|
getTwosComplement(&m_c12, 17); |
||||||
|
getTwosComplement(&m_c20, 15); |
||||||
|
getTwosComplement(&m_c21, 14); |
||||||
|
getTwosComplement(&m_c30, 12); |
||||||
|
|
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t Dps422::flushFIFO() |
||||||
|
{ |
||||||
|
return writeByteBitfield(1U, registers[FIFO_FL]); |
||||||
|
} |
||||||
|
|
||||||
|
float Dps422::calcTemp(int32_t raw) |
||||||
|
{ |
||||||
|
m_lastTempScal = (float)raw / 1048576; |
||||||
|
float u = m_lastTempScal / (1 + DPS422_ALPHA * m_lastTempScal); |
||||||
|
return (a_prime * u + b_prime); |
||||||
|
} |
||||||
|
|
||||||
|
float Dps422::calcPressure(int32_t raw_prs) |
||||||
|
{ |
||||||
|
float prs = raw_prs; |
||||||
|
prs /= scaling_facts[m_prsOsr]; |
||||||
|
|
||||||
|
float temp = (8.5 * m_lastTempScal) / (1 + 8.8 * m_lastTempScal); |
||||||
|
|
||||||
|
prs = m_c00 + m_c10 * prs + m_c01 * temp + m_c20 * prs * prs + m_c02 * temp * temp + m_c30 * prs * prs * prs + |
||||||
|
m_c11 * temp * prs + m_c12 * prs * temp * temp + m_c21 * prs * prs * temp; |
||||||
|
return prs; |
||||||
|
} |
@ -0,0 +1,55 @@ |
|||||||
|
/**
|
||||||
|
* @brief
|
||||||
|
*
|
||||||
|
* Temperature measurements must be enabled for the DPS422 to compensate for temperature drift in the pressure measurement. |
||||||
|
* @file Dps422.h |
||||||
|
* @author Infineon Technologies |
||||||
|
* @date 2018-08-22 |
||||||
|
*/ |
||||||
|
|
||||||
|
#ifndef DPS422_H_INCLUDED |
||||||
|
#define DPS422_H_INCLUDED |
||||||
|
#include "DpsClass.h" |
||||||
|
#include "util/dps422_config.h" |
||||||
|
|
||||||
|
class Dps422 : public DpsClass |
||||||
|
{ |
||||||
|
public: |
||||||
|
int16_t getContResults(float *tempBuffer, uint8_t &tempCount, float *prsBuffer, uint8_t &prsCount); |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Set the source of interrupt (FIFO full, measurement values ready) |
||||||
|
*
|
||||||
|
* @param intr_source Source of interrupt as defined by Interrupt_source_420_e |
||||||
|
* @param polarity
|
||||||
|
* @return int16_t
|
||||||
|
*/ |
||||||
|
int16_t setInterruptSources(uint8_t intr_source, uint8_t polarity = 1); |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief measures both temperature and pressure values, when op mode is set to CMD_BOTH |
||||||
|
*
|
||||||
|
* @param prs reference to the pressure value |
||||||
|
* @param temp prs reference to the temperature value |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t measureBothOnce(float &prs, float &temp); // might make sense to declare in base class for future sensors
|
||||||
|
|
||||||
|
int16_t measureBothOnce(float &prs, float &temp, uint8_t prs_osr, uint8_t temp_osr); |
||||||
|
|
||||||
|
protected: |
||||||
|
//compensation coefficients (for simplicity use 32 bits)
|
||||||
|
float a_prime; |
||||||
|
float b_prime; |
||||||
|
int32_t m_c02; |
||||||
|
int32_t m_c12; |
||||||
|
|
||||||
|
/////// implement pure virtual functions ///////
|
||||||
|
void init(void); |
||||||
|
int16_t readcoeffs(void); |
||||||
|
int16_t flushFIFO(); |
||||||
|
float calcTemp(int32_t raw); |
||||||
|
float calcPressure(int32_t raw); |
||||||
|
}; |
||||||
|
|
||||||
|
#endif |
@ -0,0 +1,803 @@ |
|||||||
|
#include "DpsClass.h" |
||||||
|
using namespace dps; |
||||||
|
|
||||||
|
const int32_t DpsClass::scaling_facts[DPS__NUM_OF_SCAL_FACTS] = {524288, 1572864, 3670016, 7864320, 253952, 516096, 1040384, 2088960}; |
||||||
|
|
||||||
|
//////// Constructor, Destructor, begin, end ////////
|
||||||
|
|
||||||
|
DpsClass::DpsClass(void) |
||||||
|
{ |
||||||
|
//assume that initialization has failed before it has been done
|
||||||
|
m_initFail = 1U; |
||||||
|
} |
||||||
|
|
||||||
|
DpsClass::~DpsClass(void) |
||||||
|
{ |
||||||
|
end(); |
||||||
|
} |
||||||
|
|
||||||
|
void DpsClass::begin(TwoWire &bus) |
||||||
|
{ |
||||||
|
begin(bus, DPS__STD_SLAVE_ADDRESS); |
||||||
|
} |
||||||
|
|
||||||
|
void DpsClass::begin(TwoWire &bus, uint8_t slaveAddress) |
||||||
|
{ |
||||||
|
//this flag will show if the initialization was successful
|
||||||
|
m_initFail = 0U; |
||||||
|
|
||||||
|
//Set I2C bus connection
|
||||||
|
m_SpiI2c = 1U; |
||||||
|
m_i2cbus = &bus; |
||||||
|
m_slaveAddress = slaveAddress; |
||||||
|
|
||||||
|
// Init bus
|
||||||
|
m_i2cbus->begin(); |
||||||
|
|
||||||
|
delay(50); //startup time of Dps310
|
||||||
|
|
||||||
|
init(); |
||||||
|
} |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
void DpsClass::begin(SPIClass &bus, int32_t chipSelect) |
||||||
|
{ |
||||||
|
begin(bus, chipSelect, 0U); |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
void DpsClass::begin(SPIClass &bus, int32_t chipSelect, uint8_t threeWire) |
||||||
|
{ |
||||||
|
//this flag will show if the initialization was successful
|
||||||
|
m_initFail = 0U; |
||||||
|
|
||||||
|
//Set SPI bus connection
|
||||||
|
m_SpiI2c = 0U; |
||||||
|
m_spibus = &bus; |
||||||
|
m_chipSelect = chipSelect; |
||||||
|
|
||||||
|
// Init bus
|
||||||
|
m_spibus->begin(); |
||||||
|
m_spibus->setDataMode(SPI_MODE3); |
||||||
|
|
||||||
|
pinMode(m_chipSelect, OUTPUT); |
||||||
|
digitalWrite(m_chipSelect, HIGH); |
||||||
|
|
||||||
|
delay(50); //startup time of Dps310
|
||||||
|
|
||||||
|
//switch to 3-wire mode if necessary
|
||||||
|
//do not use writeByteBitfield or check option to set SPI mode!
|
||||||
|
//Reading is not possible until SPI-mode is valid
|
||||||
|
if (threeWire) |
||||||
|
{ |
||||||
|
m_threeWire = 1U; |
||||||
|
if (writeByte(DPS310__REG_ADR_SPI3W, DPS310__REG_CONTENT_SPI3W)) |
||||||
|
{ |
||||||
|
m_initFail = 1U; |
||||||
|
return; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
init(); |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
void DpsClass::end(void) |
||||||
|
{ |
||||||
|
standby(); |
||||||
|
} |
||||||
|
|
||||||
|
//////// Declaration of other public functions starts here ////////
|
||||||
|
|
||||||
|
uint8_t DpsClass::getProductId(void) |
||||||
|
{ |
||||||
|
return m_productID; |
||||||
|
} |
||||||
|
|
||||||
|
uint8_t DpsClass::getRevisionId(void) |
||||||
|
{ |
||||||
|
return m_revisionID; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::getContResults(float *tempBuffer, |
||||||
|
uint8_t &tempCount, |
||||||
|
float *prsBuffer, |
||||||
|
uint8_t &prsCount, RegMask_t fifo_empty_reg) |
||||||
|
{ |
||||||
|
if (m_initFail) |
||||||
|
{ |
||||||
|
return DPS__FAIL_INIT_FAILED; |
||||||
|
} |
||||||
|
//abort if device is not in background mode
|
||||||
|
if (!(m_opMode & 0x04)) |
||||||
|
{ |
||||||
|
return DPS__FAIL_TOOBUSY; |
||||||
|
} |
||||||
|
|
||||||
|
if (!tempBuffer || !prsBuffer) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
tempCount = 0U; |
||||||
|
prsCount = 0U; |
||||||
|
|
||||||
|
//while FIFO is not empty
|
||||||
|
while (readByteBitfield(fifo_empty_reg) == 0) |
||||||
|
{ |
||||||
|
int32_t raw_result; |
||||||
|
float result; |
||||||
|
//read next result from FIFO
|
||||||
|
int16_t type = getFIFOvalue(&raw_result); |
||||||
|
switch (type) |
||||||
|
{ |
||||||
|
case 0: //temperature
|
||||||
|
if (tempCount < DPS__FIFO_SIZE) |
||||||
|
{ |
||||||
|
result = calcTemp(raw_result); |
||||||
|
tempBuffer[tempCount++] = result; |
||||||
|
} |
||||||
|
break; |
||||||
|
case 1: //pressure
|
||||||
|
if (prsCount < DPS__FIFO_SIZE) |
||||||
|
{ |
||||||
|
result = calcPressure(raw_result); |
||||||
|
prsBuffer[prsCount++] = result; |
||||||
|
} |
||||||
|
break; |
||||||
|
case -1: //read failed
|
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::getSingleResult(float &result) |
||||||
|
{ |
||||||
|
//abort if initialization failed
|
||||||
|
if (m_initFail) |
||||||
|
{ |
||||||
|
return DPS__FAIL_INIT_FAILED; |
||||||
|
} |
||||||
|
|
||||||
|
//read finished bit for current opMode
|
||||||
|
int16_t rdy; |
||||||
|
switch (m_opMode) |
||||||
|
{ |
||||||
|
case CMD_TEMP: //temperature
|
||||||
|
rdy = readByteBitfield(config_registers[TEMP_RDY]); |
||||||
|
break; |
||||||
|
case CMD_PRS: //pressure
|
||||||
|
rdy = readByteBitfield(config_registers[PRS_RDY]); |
||||||
|
break; |
||||||
|
default: //DPS310 not in command mode
|
||||||
|
return DPS__FAIL_TOOBUSY; |
||||||
|
} |
||||||
|
//read new measurement result
|
||||||
|
switch (rdy) |
||||||
|
{ |
||||||
|
case DPS__FAIL_UNKNOWN: //could not read ready flag
|
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
case 0: //ready flag not set, measurement still in progress
|
||||||
|
return DPS__FAIL_UNFINISHED; |
||||||
|
case 1: //measurement ready, expected case
|
||||||
|
Mode oldMode = m_opMode; |
||||||
|
m_opMode = IDLE; //opcode was automatically reseted by DPS310
|
||||||
|
int32_t raw_val; |
||||||
|
switch (oldMode) |
||||||
|
{ |
||||||
|
case CMD_TEMP: //temperature
|
||||||
|
getRawResult(&raw_val, registerBlocks[TEMP]); |
||||||
|
result = calcTemp(raw_val); |
||||||
|
return DPS__SUCCEEDED; // TODO
|
||||||
|
case CMD_PRS: //pressure
|
||||||
|
getRawResult(&raw_val, registerBlocks[PRS]); |
||||||
|
result = calcPressure(raw_val); |
||||||
|
return DPS__SUCCEEDED; // TODO
|
||||||
|
default: |
||||||
|
return DPS__FAIL_UNKNOWN; //should already be filtered above
|
||||||
|
} |
||||||
|
} |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::measureTempOnce(float &result) |
||||||
|
{ |
||||||
|
return measureTempOnce(result, m_tempOsr); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::measureTempOnce(float &result, uint8_t oversamplingRate) |
||||||
|
{ |
||||||
|
//Start measurement
|
||||||
|
int16_t ret = startMeasureTempOnce(oversamplingRate); |
||||||
|
if (ret != DPS__SUCCEEDED) |
||||||
|
{ |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
//wait until measurement is finished
|
||||||
|
delay(calcBusyTime(0U, m_tempOsr) / DPS__BUSYTIME_SCALING); |
||||||
|
delay(DPS310__BUSYTIME_FAILSAFE); |
||||||
|
|
||||||
|
ret = getSingleResult(result); |
||||||
|
if (ret != DPS__SUCCEEDED) |
||||||
|
{ |
||||||
|
standby(); |
||||||
|
} |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::startMeasureTempOnce(void) |
||||||
|
{ |
||||||
|
return startMeasureTempOnce(m_tempOsr); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::startMeasureTempOnce(uint8_t oversamplingRate) |
||||||
|
{ |
||||||
|
//abort if initialization failed
|
||||||
|
if (m_initFail) |
||||||
|
{ |
||||||
|
return DPS__FAIL_INIT_FAILED; |
||||||
|
} |
||||||
|
//abort if device is not in idling mode
|
||||||
|
if (m_opMode != IDLE) |
||||||
|
{ |
||||||
|
return DPS__FAIL_TOOBUSY; |
||||||
|
} |
||||||
|
|
||||||
|
if (oversamplingRate != m_tempOsr) |
||||||
|
{ |
||||||
|
//configuration of oversampling rate
|
||||||
|
if (configTemp(0U, oversamplingRate) != DPS__SUCCEEDED) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
//set device to temperature measuring mode
|
||||||
|
return setOpMode(CMD_TEMP); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::measurePressureOnce(float &result) |
||||||
|
{ |
||||||
|
return measurePressureOnce(result, m_prsOsr); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::measurePressureOnce(float &result, uint8_t oversamplingRate) |
||||||
|
{ |
||||||
|
//start the measurement
|
||||||
|
int16_t ret = startMeasurePressureOnce(oversamplingRate); |
||||||
|
if (ret != DPS__SUCCEEDED) |
||||||
|
{ |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
//wait until measurement is finished
|
||||||
|
delay(calcBusyTime(0U, m_prsOsr) / DPS__BUSYTIME_SCALING); |
||||||
|
delay(DPS310__BUSYTIME_FAILSAFE); |
||||||
|
|
||||||
|
ret = getSingleResult(result); |
||||||
|
if (ret != DPS__SUCCEEDED) |
||||||
|
{ |
||||||
|
standby(); |
||||||
|
} |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::startMeasurePressureOnce(void) |
||||||
|
{ |
||||||
|
return startMeasurePressureOnce(m_prsOsr); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::startMeasurePressureOnce(uint8_t oversamplingRate) |
||||||
|
{ |
||||||
|
//abort if initialization failed
|
||||||
|
if (m_initFail) |
||||||
|
{ |
||||||
|
return DPS__FAIL_INIT_FAILED; |
||||||
|
} |
||||||
|
//abort if device is not in idling mode
|
||||||
|
if (m_opMode != IDLE) |
||||||
|
{ |
||||||
|
return DPS__FAIL_TOOBUSY; |
||||||
|
} |
||||||
|
//configuration of oversampling rate, lowest measure rate to avoid conflicts
|
||||||
|
if (oversamplingRate != m_prsOsr) |
||||||
|
{ |
||||||
|
if (configPressure(0U, oversamplingRate)) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
} |
||||||
|
//set device to pressure measuring mode
|
||||||
|
return setOpMode(CMD_PRS); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::startMeasureTempCont(uint8_t measureRate, uint8_t oversamplingRate) |
||||||
|
{ |
||||||
|
//abort if initialization failed
|
||||||
|
if (m_initFail) |
||||||
|
{ |
||||||
|
return DPS__FAIL_INIT_FAILED; |
||||||
|
} |
||||||
|
//abort if device is not in idling mode
|
||||||
|
if (m_opMode != IDLE) |
||||||
|
{ |
||||||
|
return DPS__FAIL_TOOBUSY; |
||||||
|
} |
||||||
|
//abort if speed and precision are too high
|
||||||
|
if (calcBusyTime(measureRate, oversamplingRate) >= DPS310__MAX_BUSYTIME) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNFINISHED; |
||||||
|
} |
||||||
|
//update precision and measuring rate
|
||||||
|
if (configTemp(measureRate, oversamplingRate)) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
|
||||||
|
if (enableFIFO()) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
//Start measuring in background mode
|
||||||
|
if (DpsClass::setOpMode(CONT_TMP)) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::startMeasurePressureCont(uint8_t measureRate, uint8_t oversamplingRate) |
||||||
|
{ |
||||||
|
//abort if initialization failed
|
||||||
|
if (m_initFail) |
||||||
|
{ |
||||||
|
return DPS__FAIL_INIT_FAILED; |
||||||
|
} |
||||||
|
//abort if device is not in idling mode
|
||||||
|
if (m_opMode != IDLE) |
||||||
|
{ |
||||||
|
return DPS__FAIL_TOOBUSY; |
||||||
|
} |
||||||
|
//abort if speed and precision are too high
|
||||||
|
if (calcBusyTime(measureRate, oversamplingRate) >= DPS310__MAX_BUSYTIME) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNFINISHED; |
||||||
|
} |
||||||
|
//update precision and measuring rate
|
||||||
|
if (configPressure(measureRate, oversamplingRate)) |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
//enable result FIFO
|
||||||
|
if (enableFIFO()) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
//Start measuring in background mode
|
||||||
|
if (DpsClass::setOpMode(CONT_PRS)) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::startMeasureBothCont(uint8_t tempMr, |
||||||
|
uint8_t tempOsr, |
||||||
|
uint8_t prsMr, |
||||||
|
uint8_t prsOsr) |
||||||
|
{ |
||||||
|
//abort if initialization failed
|
||||||
|
if (m_initFail) |
||||||
|
{ |
||||||
|
return DPS__FAIL_INIT_FAILED; |
||||||
|
} |
||||||
|
//abort if device is not in idling mode
|
||||||
|
if (m_opMode != IDLE) |
||||||
|
{ |
||||||
|
return DPS__FAIL_TOOBUSY; |
||||||
|
} |
||||||
|
//abort if speed and precision are too high
|
||||||
|
if (calcBusyTime(tempMr, tempOsr) + calcBusyTime(prsMr, prsOsr) >= DPS310__MAX_BUSYTIME) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNFINISHED; |
||||||
|
} |
||||||
|
//update precision and measuring rate
|
||||||
|
if (configTemp(tempMr, tempOsr)) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
//update precision and measuring rate
|
||||||
|
if (configPressure(prsMr, prsOsr)) |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
//enable result FIFO
|
||||||
|
if (enableFIFO()) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
//Start measuring in background mode
|
||||||
|
if (setOpMode(CONT_BOTH)) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::standby(void) |
||||||
|
{ |
||||||
|
//abort if initialization failed
|
||||||
|
if (m_initFail) |
||||||
|
{ |
||||||
|
return DPS__FAIL_INIT_FAILED; |
||||||
|
} |
||||||
|
//set device to idling mode
|
||||||
|
int16_t ret = setOpMode(IDLE); |
||||||
|
if (ret != DPS__SUCCEEDED) |
||||||
|
{ |
||||||
|
return ret; |
||||||
|
} |
||||||
|
ret = disableFIFO(); |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::correctTemp(void) |
||||||
|
{ |
||||||
|
if (m_initFail) |
||||||
|
{ |
||||||
|
return DPS__FAIL_INIT_FAILED; |
||||||
|
} |
||||||
|
writeByte(0x0E, 0xA5); |
||||||
|
writeByte(0x0F, 0x96); |
||||||
|
writeByte(0x62, 0x02); |
||||||
|
writeByte(0x0E, 0x00); |
||||||
|
writeByte(0x0F, 0x00); |
||||||
|
|
||||||
|
//perform a first temperature measurement (again)
|
||||||
|
//the most recent temperature will be saved internally
|
||||||
|
//and used for compensation when calculating pressure
|
||||||
|
float trash; |
||||||
|
measureTempOnce(trash); |
||||||
|
|
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::getIntStatusFifoFull(void) |
||||||
|
{ |
||||||
|
return readByteBitfield(config_registers[INT_FLAG_FIFO]); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::getIntStatusTempReady(void) |
||||||
|
{ |
||||||
|
return readByteBitfield(config_registers[INT_FLAG_TEMP]); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::getIntStatusPrsReady(void) |
||||||
|
{ |
||||||
|
return readByteBitfield(config_registers[INT_FLAG_PRS]); |
||||||
|
} |
||||||
|
|
||||||
|
//////// Declaration of private functions starts here ////////
|
||||||
|
|
||||||
|
int16_t DpsClass::setOpMode(uint8_t opMode) |
||||||
|
{ |
||||||
|
if (writeByteBitfield(opMode, config_registers[MSR_CTRL]) == -1) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
m_opMode = (Mode)opMode; |
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::configTemp(uint8_t tempMr, uint8_t tempOsr) |
||||||
|
{ |
||||||
|
tempMr &= 0x07; |
||||||
|
tempOsr &= 0x07; |
||||||
|
// two accesses to the same register; for readability
|
||||||
|
int16_t ret = writeByteBitfield(tempMr, config_registers[TEMP_MR]); |
||||||
|
ret = writeByteBitfield(tempOsr, config_registers[TEMP_OSR]); |
||||||
|
|
||||||
|
//abort immediately on fail
|
||||||
|
if (ret != DPS__SUCCEEDED) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
m_tempMr = tempMr; |
||||||
|
m_tempOsr = tempOsr; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::configPressure(uint8_t prsMr, uint8_t prsOsr) |
||||||
|
{ |
||||||
|
prsMr &= 0x07; |
||||||
|
prsOsr &= 0x07; |
||||||
|
int16_t ret = writeByteBitfield(prsMr, config_registers[PRS_MR]); |
||||||
|
ret = writeByteBitfield(prsOsr, config_registers[PRS_OSR]); |
||||||
|
|
||||||
|
//abort immediately on fail
|
||||||
|
if (ret != DPS__SUCCEEDED) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
m_prsMr = prsMr; |
||||||
|
m_prsOsr = prsOsr; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::enableFIFO() |
||||||
|
{ |
||||||
|
return writeByteBitfield(1U, config_registers[FIFO_EN]); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::disableFIFO() |
||||||
|
{ |
||||||
|
int16_t ret = flushFIFO(); |
||||||
|
ret = writeByteBitfield(0U, config_registers[FIFO_EN]); |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
uint16_t DpsClass::calcBusyTime(uint16_t mr, uint16_t osr) |
||||||
|
{ |
||||||
|
//formula from datasheet (optimized)
|
||||||
|
return ((uint32_t)20U << mr) + ((uint32_t)16U << (osr + mr)); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::getFIFOvalue(int32_t *value) |
||||||
|
{ |
||||||
|
uint8_t buffer[DPS__RESULT_BLOCK_LENGTH] = {0}; |
||||||
|
|
||||||
|
//abort on invalid argument or failed block reading
|
||||||
|
if (value == NULL || readBlock(registerBlocks[PRS], buffer) != DPS__RESULT_BLOCK_LENGTH) |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
*value = (uint32_t)buffer[0] << 16 | (uint32_t)buffer[1] << 8 | (uint32_t)buffer[2]; |
||||||
|
getTwosComplement(value, 24); |
||||||
|
return buffer[2] & 0x01; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::readByte(uint8_t regAddress) |
||||||
|
{ |
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
//delegate to specialized function if Dps310 is connected via SPI
|
||||||
|
if (m_SpiI2c == 0) |
||||||
|
{ |
||||||
|
return readByteSPI(regAddress); |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
m_i2cbus->beginTransmission(m_slaveAddress); |
||||||
|
m_i2cbus->write(regAddress); |
||||||
|
m_i2cbus->endTransmission(false); |
||||||
|
//request 1 byte from slave
|
||||||
|
if (m_i2cbus->requestFrom(m_slaveAddress, 1U, 1U) > 0) |
||||||
|
{ |
||||||
|
return m_i2cbus->read(); //return this byte on success
|
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; //if 0 bytes were read successfully
|
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
int16_t DpsClass::readByteSPI(uint8_t regAddress) |
||||||
|
{ |
||||||
|
//this function is only made for communication via SPI
|
||||||
|
if (m_SpiI2c != 0) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
//mask regAddress
|
||||||
|
regAddress &= ~DPS310__SPI_RW_MASK; |
||||||
|
//reserve and initialize bus
|
||||||
|
m_spibus->beginTransaction(SPISettings(DPS310__SPI_MAX_FREQ, |
||||||
|
MSBFIRST, |
||||||
|
SPI_MODE3)); |
||||||
|
//enable ChipSelect for Dps310
|
||||||
|
digitalWrite(m_chipSelect, LOW); |
||||||
|
//send address with read command to Dps310
|
||||||
|
m_spibus->transfer(regAddress | DPS310__SPI_READ_CMD); |
||||||
|
//receive register content from Dps310
|
||||||
|
uint8_t ret = m_spibus->transfer(0xFF); //send a dummy byte while receiving
|
||||||
|
//disable ChipSelect for Dps310
|
||||||
|
digitalWrite(m_chipSelect, HIGH); |
||||||
|
//close current SPI transaction
|
||||||
|
m_spibus->endTransaction(); |
||||||
|
//return received data
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
int16_t DpsClass::readBlockSPI(RegBlock_t regBlock, uint8_t *buffer) |
||||||
|
{ |
||||||
|
//this function is only made for communication via SPI
|
||||||
|
if (m_SpiI2c != 0) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
//do not read if there is no buffer
|
||||||
|
if (buffer == NULL) |
||||||
|
{ |
||||||
|
return 0; //0 bytes were read successfully
|
||||||
|
} |
||||||
|
//mask regAddress
|
||||||
|
regBlock.regAddress &= ~DPS310__SPI_RW_MASK; |
||||||
|
//reserve and initialize bus
|
||||||
|
m_spibus->beginTransaction(SPISettings(DPS310__SPI_MAX_FREQ, |
||||||
|
MSBFIRST, |
||||||
|
SPI_MODE3)); |
||||||
|
//enable ChipSelect for Dps310
|
||||||
|
digitalWrite(m_chipSelect, LOW); |
||||||
|
//send address with read command to Dps310
|
||||||
|
m_spibus->transfer(regBlock.regAddress | DPS310__SPI_READ_CMD); |
||||||
|
|
||||||
|
//receive register contents from Dps310
|
||||||
|
for (uint8_t count = 0; count < regBlock.length; count++) |
||||||
|
{ |
||||||
|
buffer[count] = m_spibus->transfer(0xFF); //send a dummy byte while receiving
|
||||||
|
} |
||||||
|
|
||||||
|
//disable ChipSelect for Dps310
|
||||||
|
digitalWrite(m_chipSelect, HIGH); |
||||||
|
//close current SPI transaction
|
||||||
|
m_spibus->endTransaction(); |
||||||
|
//return received data
|
||||||
|
return regBlock.length; |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
int16_t DpsClass::writeByte(uint8_t regAddress, uint8_t data) |
||||||
|
{ |
||||||
|
return writeByte(regAddress, data, 0U); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::writeByte(uint8_t regAddress, uint8_t data, uint8_t check) |
||||||
|
{ |
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
//delegate to specialized function if Dps310 is connected via SPI
|
||||||
|
if (m_SpiI2c == 0) |
||||||
|
{ |
||||||
|
return writeByteSpi(regAddress, data, check); |
||||||
|
} |
||||||
|
#endif |
||||||
|
m_i2cbus->beginTransmission(m_slaveAddress); |
||||||
|
m_i2cbus->write(regAddress); //Write Register number to buffer
|
||||||
|
m_i2cbus->write(data); //Write data to buffer
|
||||||
|
if (m_i2cbus->endTransmission() != 0) //Send buffer content to slave
|
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
if (check == 0) |
||||||
|
return 0; //no checking
|
||||||
|
if (readByte(regAddress) == data) //check if desired by calling function
|
||||||
|
{ |
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
int16_t DpsClass::writeByteSpi(uint8_t regAddress, uint8_t data, uint8_t check) |
||||||
|
{ |
||||||
|
//this function is only made for communication via SPI
|
||||||
|
if (m_SpiI2c != 0) |
||||||
|
{ |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
//mask regAddress
|
||||||
|
regAddress &= ~DPS310__SPI_RW_MASK; |
||||||
|
//reserve and initialize bus
|
||||||
|
m_spibus->beginTransaction(SPISettings(DPS310__SPI_MAX_FREQ, |
||||||
|
MSBFIRST, |
||||||
|
SPI_MODE3)); |
||||||
|
//enable ChipSelect for Dps310
|
||||||
|
digitalWrite(m_chipSelect, LOW); |
||||||
|
//send address with read command to Dps310
|
||||||
|
m_spibus->transfer(regAddress | DPS310__SPI_WRITE_CMD); |
||||||
|
|
||||||
|
//write register content from Dps310
|
||||||
|
m_spibus->transfer(data); |
||||||
|
|
||||||
|
//disable ChipSelect for Dps310
|
||||||
|
digitalWrite(m_chipSelect, HIGH); |
||||||
|
//close current SPI transaction
|
||||||
|
m_spibus->endTransaction(); |
||||||
|
|
||||||
|
//check if necessary
|
||||||
|
if (check == 0) |
||||||
|
{ |
||||||
|
//no checking necessary
|
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
//checking necessary
|
||||||
|
if (readByte(regAddress) == data) |
||||||
|
{ |
||||||
|
//check passed
|
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
//check failed
|
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
} |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
int16_t DpsClass::writeByteBitfield(uint8_t data, RegMask_t regMask) |
||||||
|
{ |
||||||
|
return writeByteBitfield(data, regMask.regAddress, regMask.mask, regMask.shift, 0U); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::writeByteBitfield(uint8_t data, |
||||||
|
uint8_t regAddress, |
||||||
|
uint8_t mask, |
||||||
|
uint8_t shift, |
||||||
|
uint8_t check) |
||||||
|
{ |
||||||
|
int16_t old = readByte(regAddress); |
||||||
|
if (old < 0) |
||||||
|
{ |
||||||
|
//fail while reading
|
||||||
|
return old; |
||||||
|
} |
||||||
|
return writeByte(regAddress, ((uint8_t)old & ~mask) | ((data << shift) & mask), check); |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::readByteBitfield(RegMask_t regMask) |
||||||
|
{ |
||||||
|
int16_t ret = readByte(regMask.regAddress); |
||||||
|
if (ret < 0) |
||||||
|
{ |
||||||
|
return ret; |
||||||
|
} |
||||||
|
return (((uint8_t)ret) & regMask.mask) >> regMask.shift; |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::readBlock(RegBlock_t regBlock, uint8_t *buffer) |
||||||
|
{ |
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
//delegate to specialized function if Dps310 is connected via SPI
|
||||||
|
if (m_SpiI2c == 0) |
||||||
|
{ |
||||||
|
return readBlockSPI(regBlock, buffer); |
||||||
|
} |
||||||
|
#endif |
||||||
|
//do not read if there is no buffer
|
||||||
|
if (buffer == NULL) |
||||||
|
{ |
||||||
|
return 0; //0 bytes read successfully
|
||||||
|
} |
||||||
|
|
||||||
|
m_i2cbus->beginTransmission(m_slaveAddress); |
||||||
|
m_i2cbus->write(regBlock.regAddress); |
||||||
|
m_i2cbus->endTransmission(false); |
||||||
|
//request length bytes from slave
|
||||||
|
int16_t ret = m_i2cbus->requestFrom(m_slaveAddress, regBlock.length, 1U); |
||||||
|
//read all received bytes to buffer
|
||||||
|
for (int16_t count = 0; count < ret; count++) |
||||||
|
{ |
||||||
|
buffer[count] = m_i2cbus->read(); |
||||||
|
} |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
void DpsClass::getTwosComplement(int32_t *raw, uint8_t length) |
||||||
|
{ |
||||||
|
if (*raw & ((uint32_t)1 << (length - 1))) |
||||||
|
{ |
||||||
|
*raw -= (uint32_t)1 << length; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
int16_t DpsClass::getRawResult(int32_t *raw, RegBlock_t reg) |
||||||
|
{ |
||||||
|
uint8_t buffer[DPS__RESULT_BLOCK_LENGTH] = {0}; |
||||||
|
if (readBlock(reg, buffer) != DPS__RESULT_BLOCK_LENGTH) |
||||||
|
return DPS__FAIL_UNKNOWN; |
||||||
|
|
||||||
|
*raw = (uint32_t)buffer[0] << 16 | (uint32_t)buffer[1] << 8 | (uint32_t)buffer[2]; |
||||||
|
getTwosComplement(raw, 24); |
||||||
|
return DPS__SUCCEEDED; |
||||||
|
} |
@ -0,0 +1,485 @@ |
|||||||
|
/**
|
||||||
|
* Arduino library to control Dps310 |
||||||
|
* |
||||||
|
* "Dps310" represents Infineon's high-sensetive pressure and temperature sensor.
|
||||||
|
* It measures in ranges of 300 - 1200 hPa and -40 and 85 °C.
|
||||||
|
* The sensor can be connected via SPI or I2C.
|
||||||
|
* It is able to perform single measurements |
||||||
|
* or to perform continuous measurements of temperature and pressure at the same time,
|
||||||
|
* and stores the results in a FIFO to reduce bus communication.
|
||||||
|
* |
||||||
|
* Have a look at the datasheet for more information.
|
||||||
|
*/ |
||||||
|
|
||||||
|
#ifndef DPSCLASS_H_INCLUDED |
||||||
|
#define DPSCLASS_H_INCLUDED |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
#include <SPI.h> |
||||||
|
#endif |
||||||
|
#include <Wire.h> |
||||||
|
#include "util/dps_config.h" |
||||||
|
#include <Arduino.h> |
||||||
|
|
||||||
|
class DpsClass |
||||||
|
{ |
||||||
|
public: |
||||||
|
//constructor
|
||||||
|
DpsClass(void); |
||||||
|
//destructor
|
||||||
|
~DpsClass(void); |
||||||
|
|
||||||
|
/**
|
||||||
|
* I2C begin function with standard address |
||||||
|
*/ |
||||||
|
void begin(TwoWire &bus); |
||||||
|
|
||||||
|
/**
|
||||||
|
* Standard I2C begin function |
||||||
|
* |
||||||
|
* @param &bus: I2CBus which connects MC to the sensor |
||||||
|
* @param slaveAddress: I2C address of the sensor (0x77 or 0x76) |
||||||
|
*/ |
||||||
|
void begin(TwoWire &bus, uint8_t slaveAddress); |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
/**
|
||||||
|
* SPI begin function for Dps310 with 4-wire SPI |
||||||
|
*/ |
||||||
|
void begin(SPIClass &bus, int32_t chipSelect); |
||||||
|
#endif |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
/**
|
||||||
|
* Standard SPI begin function |
||||||
|
* |
||||||
|
* @param &bus: SPI bus which connects MC to Dps310 |
||||||
|
* @param chipSelect: Number of the CS line for the Dps310 |
||||||
|
* @param threeWire: 1 if Dps310 is connected with 3-wire SPI |
||||||
|
* 0 if Dps310 is connected with 4-wire SPI (standard) |
||||||
|
*/ |
||||||
|
void begin(SPIClass &bus, int32_t chipSelect, uint8_t threeWire); |
||||||
|
#endif |
||||||
|
|
||||||
|
/**
|
||||||
|
* End function for Dps310 |
||||||
|
* Sets the sensor to idle mode |
||||||
|
*/ |
||||||
|
void end(void); |
||||||
|
|
||||||
|
/**
|
||||||
|
* returns the Product ID of the connected Dps310 sensor |
||||||
|
*/ |
||||||
|
uint8_t getProductId(void); |
||||||
|
|
||||||
|
/**
|
||||||
|
* returns the Revision ID of the connected Dps310 sensor |
||||||
|
*/ |
||||||
|
uint8_t getRevisionId(void); |
||||||
|
|
||||||
|
/**
|
||||||
|
* Sets the Dps310 to standby mode |
||||||
|
* |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t standby(void); |
||||||
|
|
||||||
|
/**
|
||||||
|
* performs one temperature measurement |
||||||
|
* |
||||||
|
* @param &result: reference to a float value where the result will be written |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t measureTempOnce(float &result); |
||||||
|
|
||||||
|
/**
|
||||||
|
* performs one temperature measurement with specified oversamplingRate |
||||||
|
* |
||||||
|
* @param &result: reference to a float where the result will be written |
||||||
|
* @param oversamplingRate: DPS__OVERSAMPLING_RATE_1, DPS__OVERSAMPLING_RATE_2, DPS__OVERSAMPLING_RATE_4 ... DPS__OVERSAMPLING_RATE_128, which are defined as integers 0 - 7 |
||||||
|
* The number of measurements equals to 2^n, if the value written to the register field is n. 2^n internal measurements are combined to return a more exact measurement |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t measureTempOnce(float &result, uint8_t oversamplingRate); |
||||||
|
|
||||||
|
/**
|
||||||
|
* starts a single temperature measurement |
||||||
|
* |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t startMeasureTempOnce(void); |
||||||
|
|
||||||
|
/**
|
||||||
|
* starts a single temperature measurement with specified oversamplingRate |
||||||
|
* |
||||||
|
* @param oversamplingRate: DPS__OVERSAMPLING_RATE_1, DPS__OVERSAMPLING_RATE_2, DPS__OVERSAMPLING_RATE_4 ... DPS__OVERSAMPLING_RATE_128, which are defined as integers 0 - 7 |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t startMeasureTempOnce(uint8_t oversamplingRate); |
||||||
|
|
||||||
|
/**
|
||||||
|
* performs one pressure measurement |
||||||
|
* |
||||||
|
* @param &result: reference to a float value where the result will be written |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t measurePressureOnce(float &result); |
||||||
|
|
||||||
|
/**
|
||||||
|
* performs one pressure measurement with specified oversamplingRate |
||||||
|
* |
||||||
|
* @param &result: reference to a float where the result will be written |
||||||
|
* @param oversamplingRate: DPS__OVERSAMPLING_RATE_1, DPS__OVERSAMPLING_RATE_2, DPS__OVERSAMPLING_RATE_4 ... DPS__OVERSAMPLING_RATE_128 |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t measurePressureOnce(float &result, uint8_t oversamplingRate); |
||||||
|
|
||||||
|
/**
|
||||||
|
* starts a single pressure measurement |
||||||
|
* |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t startMeasurePressureOnce(void); |
||||||
|
|
||||||
|
/**
|
||||||
|
* starts a single pressure measurement with specified oversamplingRate |
||||||
|
* |
||||||
|
* @param oversamplingRate: DPS__OVERSAMPLING_RATE_1, DPS__OVERSAMPLING_RATE_2, DPS__OVERSAMPLING_RATE_4 ... DPS__OVERSAMPLING_RATE_128 |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t startMeasurePressureOnce(uint8_t oversamplingRate); |
||||||
|
|
||||||
|
/**
|
||||||
|
* gets the result a single temperature or pressure measurement in °C or Pa |
||||||
|
* |
||||||
|
* @param &result: reference to a float value where the result will be written |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t getSingleResult(float &result); |
||||||
|
|
||||||
|
/**
|
||||||
|
* starts a continuous temperature measurement with specified measurement rate and oversampling rate |
||||||
|
* If measure rate is n and oversampling rate is m, the DPS310 performs 2^(n+m) internal measurements per second.
|
||||||
|
* The DPS310 cannot operate with high precision and high speed at the same time. Consult the datasheet for more information. |
||||||
|
*
|
||||||
|
* @param measureRate: DPS__MEASUREMENT_RATE_1, DPS__MEASUREMENT_RATE_2,DPS__MEASUREMENT_RATE_4 ... DPS__MEASUREMENT_RATE_128 |
||||||
|
* @param oversamplingRate: DPS__OVERSAMPLING_RATE_1, DPS__OVERSAMPLING_RATE_2, DPS__OVERSAMPLING_RATE_4 ... DPS__OVERSAMPLING_RATE_128 |
||||||
|
*
|
||||||
|
* @return status code |
||||||
|
*
|
||||||
|
*/ |
||||||
|
int16_t startMeasureTempCont(uint8_t measureRate, uint8_t oversamplingRate); |
||||||
|
|
||||||
|
/**
|
||||||
|
* starts a continuous temperature measurement with specified measurement rate and oversampling rate |
||||||
|
* |
||||||
|
* @param measureRate: DPS__MEASUREMENT_RATE_1, DPS__MEASUREMENT_RATE_2,DPS__MEASUREMENT_RATE_4 ... DPS__MEASUREMENT_RATE_128 |
||||||
|
* @param oversamplingRate: DPS__OVERSAMPLING_RATE_1, DPS__OVERSAMPLING_RATE_2, DPS__OVERSAMPLING_RATE_4 ... DPS__OVERSAMPLING_RATE_128 |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t startMeasurePressureCont(uint8_t measureRate, uint8_t oversamplingRate); |
||||||
|
|
||||||
|
/**
|
||||||
|
* starts a continuous temperature and pressure measurement with specified measurement rate and oversampling rate for temperature and pressure measurement respectvely. |
||||||
|
* |
||||||
|
* @param tempMr measure rate for temperature |
||||||
|
* @param tempOsr oversampling rate for temperature |
||||||
|
* @param prsMr measure rate for pressure |
||||||
|
* @param prsOsr oversampling rate for pressure |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t startMeasureBothCont(uint8_t tempMr, uint8_t tempOsr, uint8_t prsMr, uint8_t prsOsr); |
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the interrupt status flag of the FIFO |
||||||
|
* |
||||||
|
* @return 1 if the FIFO is full and caused an interrupt |
||||||
|
* 0 if the FIFO is not full or FIFO interrupt is disabled |
||||||
|
* -1 on fail |
||||||
|
*/ |
||||||
|
int16_t getIntStatusFifoFull(void); |
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the interrupt status flag that indicates a finished temperature measurement |
||||||
|
* |
||||||
|
* @return 1 if a finished temperature measurement caused an interrupt; |
||||||
|
* 0 if there is no finished temperature measurement or interrupts are disabled; |
||||||
|
* -1 on fail. |
||||||
|
*/ |
||||||
|
int16_t getIntStatusTempReady(void); |
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the interrupt status flag that indicates a finished pressure measurement |
||||||
|
* |
||||||
|
* @return 1 if a finished pressure measurement caused an interrupt;
|
||||||
|
* 0 if there is no finished pressure measurement or interrupts are disabled; |
||||||
|
* -1 on fail. |
||||||
|
*/ |
||||||
|
int16_t getIntStatusPrsReady(void); |
||||||
|
|
||||||
|
/**
|
||||||
|
* Function to fix a hardware problem on some devices |
||||||
|
* You have this problem if you measure a temperature which is too high (e.g. 60°C when temperature is around 20°C) |
||||||
|
* Call correctTemp() directly after begin() to fix this issue |
||||||
|
*/ |
||||||
|
int16_t correctTemp(void); |
||||||
|
|
||||||
|
protected: |
||||||
|
//scaling factor table
|
||||||
|
static const int32_t scaling_facts[DPS__NUM_OF_SCAL_FACTS]; |
||||||
|
|
||||||
|
dps::Mode m_opMode; |
||||||
|
|
||||||
|
//flags
|
||||||
|
uint8_t m_initFail; |
||||||
|
|
||||||
|
uint8_t m_productID; |
||||||
|
uint8_t m_revisionID; |
||||||
|
|
||||||
|
//settings
|
||||||
|
uint8_t m_tempMr; |
||||||
|
uint8_t m_tempOsr; |
||||||
|
uint8_t m_prsMr; |
||||||
|
uint8_t m_prsOsr; |
||||||
|
|
||||||
|
// compensation coefficients for both dps310 and dps422
|
||||||
|
int32_t m_c00; |
||||||
|
int32_t m_c10; |
||||||
|
int32_t m_c01; |
||||||
|
int32_t m_c11; |
||||||
|
int32_t m_c20; |
||||||
|
int32_t m_c21; |
||||||
|
int32_t m_c30; |
||||||
|
|
||||||
|
// last measured scaled temperature (necessary for pressure compensation)
|
||||||
|
float m_lastTempScal; |
||||||
|
|
||||||
|
//bus specific
|
||||||
|
uint8_t m_SpiI2c; //0=SPI, 1=I2C
|
||||||
|
|
||||||
|
//used for I2C
|
||||||
|
TwoWire *m_i2cbus; |
||||||
|
uint8_t m_slaveAddress; |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
//used for SPI
|
||||||
|
SPIClass *m_spibus; |
||||||
|
int32_t m_chipSelect; |
||||||
|
uint8_t m_threeWire; |
||||||
|
#endif |
||||||
|
/**
|
||||||
|
* Initializes the sensor. |
||||||
|
* This function has to be called from begin() |
||||||
|
* and requires a valid bus initialization. |
||||||
|
*/ |
||||||
|
virtual void init(void) = 0; |
||||||
|
|
||||||
|
/**
|
||||||
|
* reads the compensation coefficients from the sensor |
||||||
|
* this is called once from init(), which is called from begin() |
||||||
|
* |
||||||
|
* @return 0 on success, -1 on fail |
||||||
|
*/ |
||||||
|
virtual int16_t readcoeffs(void) = 0; |
||||||
|
|
||||||
|
/**
|
||||||
|
* Sets the Operation Mode of the sensor |
||||||
|
*
|
||||||
|
* @param opMode: the new OpMode as defined by dps::Mode; CMD_BOTH should not be used for DPS310 |
||||||
|
* @return 0 on success, -1 on fail |
||||||
|
*/ |
||||||
|
int16_t setOpMode(uint8_t opMode); |
||||||
|
|
||||||
|
/**
|
||||||
|
* Configures temperature measurement |
||||||
|
* |
||||||
|
* @param temp_mr: DPS__MEASUREMENT_RATE_1, DPS__MEASUREMENT_RATE_2,DPS__MEASUREMENT_RATE_4 ... DPS__MEASUREMENT_RATE_128 |
||||||
|
* @param temp_osr: DPS__OVERSAMPLING_RATE_1, DPS__OVERSAMPLING_RATE_2, DPS__OVERSAMPLING_RATE_4 ... DPS__OVERSAMPLING_RATE_128 |
||||||
|
*
|
||||||
|
* @return 0 normally or -1 on fail |
||||||
|
*/ |
||||||
|
virtual int16_t configTemp(uint8_t temp_mr, uint8_t temp_osr); |
||||||
|
|
||||||
|
/**
|
||||||
|
* Configures pressure measurement |
||||||
|
* |
||||||
|
* @param prs_mr: DPS__MEASUREMENT_RATE_1, DPS__MEASUREMENT_RATE_2,DPS__MEASUREMENT_RATE_4 ... DPS__MEASUREMENT_RATE_128 |
||||||
|
* @param prs_osr: DPS__OVERSAMPLING_RATE_1, DPS__OVERSAMPLING_RATE_2, DPS__OVERSAMPLING_RATE_4 ... DPS__OVERSAMPLING_RATE_128 |
||||||
|
* @return 0 normally or -1 on fail |
||||||
|
*/ |
||||||
|
virtual int16_t configPressure(uint8_t prs_mr, uint8_t prs_osr); |
||||||
|
|
||||||
|
virtual int16_t flushFIFO() = 0; |
||||||
|
|
||||||
|
virtual float calcTemp(int32_t raw) = 0; |
||||||
|
|
||||||
|
virtual float calcPressure(int32_t raw) = 0; |
||||||
|
|
||||||
|
int16_t enableFIFO(); |
||||||
|
|
||||||
|
int16_t disableFIFO(); |
||||||
|
|
||||||
|
/**
|
||||||
|
* calculates the time that the sensor needs for 2^mr measurements with an oversampling rate of 2^osr (see table "pressure measurement time (ms) versus oversampling rate") |
||||||
|
* Note that the total measurement time for temperature and pressure must not be more than 1 second. |
||||||
|
* Timing behavior of pressure and temperature sensors can be considered the same. |
||||||
|
*
|
||||||
|
* @param mr: DPS__MEASUREMENT_RATE_1, DPS__MEASUREMENT_RATE_2,DPS__MEASUREMENT_RATE_4 ... DPS__MEASUREMENT_RATE_128 |
||||||
|
* @param osr: DPS__OVERSAMPLING_RATE_1, DPS__OVERSAMPLING_RATE_2, DPS__OVERSAMPLING_RATE_4 ... DPS__OVERSAMPLING_RATE_128 |
||||||
|
* @return time that the sensor needs for this measurement |
||||||
|
*/ |
||||||
|
uint16_t calcBusyTime(uint16_t temp_rate, uint16_t temp_osr); |
||||||
|
|
||||||
|
/**
|
||||||
|
* reads the next raw value from the FIFO |
||||||
|
* |
||||||
|
* @param value: the raw pressure or temperature value read from the pressure register blocks, where the LSB of PRS_B0 marks wheather the value is a temperatur or a pressure. |
||||||
|
*
|
||||||
|
* @return -1 on fail |
||||||
|
* 0 if result is a temperature raw value |
||||||
|
* 1 if result is a pressure raw value |
||||||
|
*/ |
||||||
|
int16_t getFIFOvalue(int32_t *value); |
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the results from continuous measurements and writes them to given arrays |
||||||
|
* |
||||||
|
* @param *tempBuffer: The start address of the buffer where the temperature results are written |
||||||
|
* If this is NULL, no temperature results will be written out |
||||||
|
* @param &tempCount: The size of the buffer for temperature results. |
||||||
|
* When the function ends, it will contain the number of bytes written to the buffer. |
||||||
|
* @param *prsBuffer: The start address of the buffer where the pressure results are written |
||||||
|
* If this is NULL, no pressure results will be written out |
||||||
|
* @param &prsCount: The size of the buffer for pressure results. |
||||||
|
* When the function ends, it will contain the number of bytes written to the buffer. |
||||||
|
* @param reg The FIFO empty register field; needed since this field is different for each sensor |
||||||
|
* @return status code |
||||||
|
*/ |
||||||
|
int16_t getContResults(float *tempBuffer, uint8_t &tempCount, float *prsBuffer, uint8_t &prsCount, RegMask_t reg); |
||||||
|
|
||||||
|
/**
|
||||||
|
* reads a byte from the sensor |
||||||
|
* |
||||||
|
* @param regAdress: Address that has to be read |
||||||
|
* @return register content or -1 on fail |
||||||
|
*/ |
||||||
|
int16_t readByte(uint8_t regAddress); |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
/**
|
||||||
|
* reads a byte from the sensor via SPI |
||||||
|
* this function is automatically called by readByte |
||||||
|
* if the sensor is connected via SPI |
||||||
|
* |
||||||
|
* @param regAdress: Address that has to be read |
||||||
|
* @return register content or -1 on fail |
||||||
|
*/ |
||||||
|
int16_t readByteSPI(uint8_t regAddress); |
||||||
|
#endif |
||||||
|
/**
|
||||||
|
* reads a block from the sensor |
||||||
|
* |
||||||
|
* @param regAdress: Address that has to be read |
||||||
|
* @param length: Length of data block |
||||||
|
* @param buffer: Buffer where data will be stored |
||||||
|
* @return number of bytes that have been read successfully, which might not always equal to length due to rx-Buffer overflow etc. |
||||||
|
*/ |
||||||
|
int16_t readBlock(RegBlock_t regBlock, uint8_t *buffer); |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
/**
|
||||||
|
* reads a block from the sensor via SPI |
||||||
|
* |
||||||
|
* @param regAdress: Address that has to be read |
||||||
|
* @param length: Length of data block |
||||||
|
* @param readbuffer: Buffer where data will be stored |
||||||
|
* @return number of bytes that have been read successfully, which might not always equal to length due to rx-Buffer overflow etc. |
||||||
|
*/ |
||||||
|
int16_t readBlockSPI(RegBlock_t regBlock, uint8_t *readbuffer); |
||||||
|
#endif |
||||||
|
/**
|
||||||
|
* writes a byte to a given register of the sensor without checking |
||||||
|
* |
||||||
|
* @param regAdress: Address of the register that has to be updated |
||||||
|
* @param data: Byte that will be written to the register |
||||||
|
* @return 0 if byte was written successfully |
||||||
|
* or -1 on fail |
||||||
|
*/ |
||||||
|
int16_t writeByte(uint8_t regAddress, uint8_t data); |
||||||
|
|
||||||
|
/**
|
||||||
|
* writes a byte to a register of the sensor |
||||||
|
* |
||||||
|
* @param regAdress: Address of the register that has to be updated |
||||||
|
* @param data: Byte that will be written to the register |
||||||
|
* @param check: If this is true, register content will be read after writing |
||||||
|
* to check if update was successful |
||||||
|
* @return 0 if byte was written successfully |
||||||
|
* or -1 on fail |
||||||
|
*/ |
||||||
|
int16_t writeByte(uint8_t regAddress, uint8_t data, uint8_t check); |
||||||
|
|
||||||
|
#ifndef DPS_DISABLESPI |
||||||
|
/**
|
||||||
|
* writes a byte to a register of the sensor via SPI |
||||||
|
* |
||||||
|
* @param regAdress: Address of the register that has to be updated |
||||||
|
* @param data: Byte that will be written to the register |
||||||
|
* @param check: If this is true, register content will be read after writing |
||||||
|
* to check if update was successful |
||||||
|
* @return 0 if byte was written successfully |
||||||
|
* or -1 on fail |
||||||
|
*/ |
||||||
|
int16_t writeByteSpi(uint8_t regAddress, uint8_t data, uint8_t check); |
||||||
|
#endif |
||||||
|
|
||||||
|
/**
|
||||||
|
* updates a bit field of the sensor without checking |
||||||
|
* |
||||||
|
* @param regMask: Mask of the register that has to be updated |
||||||
|
* @param data: BitValues that will be written to the register |
||||||
|
* @return 0 if byte was written successfully |
||||||
|
* or -1 on fail |
||||||
|
*/ |
||||||
|
int16_t writeByteBitfield(uint8_t data, RegMask_t regMask); |
||||||
|
|
||||||
|
/**
|
||||||
|
* updates a bit field of the sensor |
||||||
|
* |
||||||
|
* regMask: Mask of the register that has to be updated |
||||||
|
* data: BitValues that will be written to the register |
||||||
|
* check: enables/disables check after writing; 0 disables check. |
||||||
|
* if check fails, -1 will be returned |
||||||
|
* @return 0 if byte was written successfully |
||||||
|
* or -1 on fail |
||||||
|
*/ |
||||||
|
int16_t writeByteBitfield(uint8_t data, uint8_t regAddress, uint8_t mask, uint8_t shift, uint8_t check); |
||||||
|
|
||||||
|
/**
|
||||||
|
* reads a bit field from the sensor |
||||||
|
* regMask: Mask of the register that has to be updated |
||||||
|
* data: BitValues that will be written to the register |
||||||
|
* @return read and processed bits |
||||||
|
* or -1 on fail |
||||||
|
*/ |
||||||
|
int16_t readByteBitfield(RegMask_t regMask); |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief converts non-32-bit negative numbers to 32-bit negative numbers with 2's complement |
||||||
|
*
|
||||||
|
* @param raw The raw number of less than 32 bits |
||||||
|
* @param length The bit length |
||||||
|
*/ |
||||||
|
void getTwosComplement(int32_t *raw, uint8_t length); |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get a raw result from a given register block |
||||||
|
*
|
||||||
|
* @param raw The address where the raw value is to be written |
||||||
|
* @param reg The register block to be read from |
||||||
|
* @return status code
|
||||||
|
*/ |
||||||
|
int16_t getRawResult(int32_t *raw, RegBlock_t reg); |
||||||
|
}; |
||||||
|
|
||||||
|
#endif //DPSCLASS_H_INCLUDED
|
@ -0,0 +1,19 @@ |
|||||||
|
#ifndef DPSREGISTER_H_INCLUDED |
||||||
|
#define DPSREGISTER_H_INCLUDED |
||||||
|
|
||||||
|
#include <Arduino.h> |
||||||
|
|
||||||
|
typedef struct |
||||||
|
{ |
||||||
|
uint8_t regAddress; |
||||||
|
uint8_t mask; |
||||||
|
uint8_t shift; |
||||||
|
} RegMask_t; |
||||||
|
|
||||||
|
typedef struct |
||||||
|
{ |
||||||
|
uint8_t regAddress; |
||||||
|
uint8_t length; |
||||||
|
} RegBlock_t; |
||||||
|
|
||||||
|
#endif |
@ -0,0 +1,49 @@ |
|||||||
|
#ifndef DPS310_CONFIG_H_ |
||||||
|
#define DPS310_CONFIG_H_ |
||||||
|
|
||||||
|
#define DPS310_NUM_OF_REGMASKS 16 |
||||||
|
|
||||||
|
enum Interrupt_source_310_e |
||||||
|
{ |
||||||
|
DPS310_NO_INTR = 0, |
||||||
|
DPS310_PRS_INTR = 1, |
||||||
|
DPS310_TEMP_INTR = 2, |
||||||
|
DPS310_BOTH_INTR = 3, |
||||||
|
DPS310_FIFO_FULL_INTR = 4, |
||||||
|
}; |
||||||
|
|
||||||
|
namespace dps310 |
||||||
|
{ |
||||||
|
|
||||||
|
enum Registers_e |
||||||
|
{ |
||||||
|
PROD_ID = 0, |
||||||
|
REV_ID, |
||||||
|
TEMP_SENSOR, // internal vs external
|
||||||
|
TEMP_SENSORREC, //temperature sensor recommendation
|
||||||
|
TEMP_SE, //temperature shift enable (if temp_osr>3)
|
||||||
|
PRS_SE, //pressure shift enable (if prs_osr>3)
|
||||||
|
FIFO_FL, //FIFO flush
|
||||||
|
FIFO_EMPTY, //FIFO empty
|
||||||
|
FIFO_FULL, //FIFO full
|
||||||
|
INT_HL, |
||||||
|
INT_SEL, //interrupt select
|
||||||
|
}; |
||||||
|
|
||||||
|
const RegMask_t registers[DPS310_NUM_OF_REGMASKS] = { |
||||||
|
{0x0D, 0x0F, 0}, // PROD_ID
|
||||||
|
{0x0D, 0xF0, 4}, // REV_ID
|
||||||
|
{0x07, 0x80, 7}, // TEMP_SENSOR
|
||||||
|
{0x28, 0x80, 7}, // TEMP_SENSORREC
|
||||||
|
{0x09, 0x08, 3}, // TEMP_SE
|
||||||
|
{0x09, 0x04, 2}, // PRS_SE
|
||||||
|
{0x0C, 0x80, 7}, // FIFO_FL
|
||||||
|
{0x0B, 0x01, 0}, // FIFO_EMPTY
|
||||||
|
{0x0B, 0x02, 1}, // FIFO_FULL
|
||||||
|
{0x09, 0x80, 7}, // INT_HL
|
||||||
|
{0x09, 0x70, 4}, // INT_SEL
|
||||||
|
}; |
||||||
|
|
||||||
|
const RegBlock_t coeffBlock = {0x10, 18}; |
||||||
|
} // namespace dps310
|
||||||
|
#endif |
@ -0,0 +1,86 @@ |
|||||||
|
|
||||||
|
#ifndef DPS422_CONFIG_H_ |
||||||
|
#define DPS422_CONFIG_H_ |
||||||
|
|
||||||
|
// consts for temperature calculation
|
||||||
|
#define DPS422_T_REF 27 |
||||||
|
#define DPS422_V_BE_TARGET 0.687027 |
||||||
|
#define DPS422_ALPHA 9.45 |
||||||
|
#define DPS422_T_C_VBE -1.735e-3 |
||||||
|
#define DPS422_K_PTAT_CORNER -0.8 |
||||||
|
#define DPS422_K_PTAT_CURVATURE 0.039 |
||||||
|
#define DPS422_A_0 5030 |
||||||
|
|
||||||
|
#define DPS422_NUM_OF_REGMASKS 20 |
||||||
|
|
||||||
|
enum Interrupt_source_420_e |
||||||
|
{ |
||||||
|
DPS422_NO_INTR = 0, |
||||||
|
DPS422_PRS_INTR = 1, |
||||||
|
DPS422_TEMP_INTR = 2, |
||||||
|
DPS422_BOTH_INTR = 3, |
||||||
|
DPS422_FIFO_WM_INTR = 4, |
||||||
|
DPS422_FIFO_FULL_INTR = 8, |
||||||
|
}; |
||||||
|
|
||||||
|
namespace dps422 |
||||||
|
{ |
||||||
|
enum Registers_e |
||||||
|
{ |
||||||
|
// flags
|
||||||
|
CONT_FLAG = 0, // continuous mode flag
|
||||||
|
INIT_DONE, // set when initialisation procedure is complete
|
||||||
|
// interrupt config
|
||||||
|
INTR_SEL, // interrupt select
|
||||||
|
INTR_POL, // interrupt active polarity
|
||||||
|
// fifo config
|
||||||
|
WM, // watermark level
|
||||||
|
FIFO_FL, // FIFO flush
|
||||||
|
FIFO_EMPTY, // FIFO empty
|
||||||
|
FIFO_FULL, // if FIFO is full or reaches watermark level
|
||||||
|
FIFO_FULL_CONF, // Configures FIFO behaviour when full
|
||||||
|
FIFO_FILL_LEVEL, //contains the number of pressure and/or temperature measurements currently stored in FIFO
|
||||||
|
// misc
|
||||||
|
PROD_ID, |
||||||
|
REV_ID, |
||||||
|
SPI_MODE, // 4- or 3-wire SPI
|
||||||
|
SOFT_RESET, |
||||||
|
MUST_SET, // bit 7 of TEMP_CFG, according to datasheet should always be set
|
||||||
|
}; |
||||||
|
|
||||||
|
const RegMask_t registers[DPS422_NUM_OF_REGMASKS] = { |
||||||
|
// flags
|
||||||
|
{0x08, 0x40, 6}, // CONT_FLAG
|
||||||
|
{0x08, 0x80, 7}, // INIT_DONE
|
||||||
|
// interrupt config
|
||||||
|
{0x09, 0xF0, 4}, // INTR_SEL
|
||||||
|
{0x09, 0x80, 3}, // INTR_POL
|
||||||
|
// /fifo config
|
||||||
|
{0x0B, 0x1F, 0}, // WM
|
||||||
|
{0x0D, 0x80, 7}, // FIFO_FL
|
||||||
|
{0x0C, 0x01, 0}, // FIFO_EMPTY
|
||||||
|
{0x0C, 0x02, 1}, // FIFO_FULL
|
||||||
|
{0x09, 0x04, 2}, // FIFO_FULL_CONF
|
||||||
|
{0x0C, 0xFC, 2}, // FIFO_FILL_LEVEL
|
||||||
|
// misc
|
||||||
|
{0x1D, 0x0F, 0}, // PROD_ID
|
||||||
|
{0x1D, 0xF0, 0}, // REV_ID
|
||||||
|
{0x09, 0x01, 0}, // SPI_MODE
|
||||||
|
{0x0D, 0x0F, 0}, // SOFT_RESET
|
||||||
|
{0x07, 0x80, 7}, // MUST_SET
|
||||||
|
}; |
||||||
|
|
||||||
|
enum RegisterBlocks_e |
||||||
|
{ |
||||||
|
COEF_TEMP, // compensation coefficients
|
||||||
|
COEF_PRS, |
||||||
|
}; |
||||||
|
|
||||||
|
const RegBlock_t coeffBlocks[4] = { |
||||||
|
{0x20, 3}, |
||||||
|
{0x26, 20}, |
||||||
|
}; |
||||||
|
|
||||||
|
} // namespace dps422
|
||||||
|
|
||||||
|
#endif /* DPS422_CONSTS_H_ */ |
@ -0,0 +1,130 @@ |
|||||||
|
|
||||||
|
#ifndef DPS_CONSTS_H_ |
||||||
|
#define DPS_CONSTS_H_ |
||||||
|
#include "util/DpsRegister.h" |
||||||
|
|
||||||
|
/////////// DPS310 ///////////
|
||||||
|
#define DPS310__PROD_ID 0x00 |
||||||
|
#define DPS310__SPI_WRITE_CMD 0x00U |
||||||
|
#define DPS310__SPI_READ_CMD 0x80U |
||||||
|
#define DPS310__SPI_RW_MASK 0x80U |
||||||
|
#define DPS310__SPI_MAX_FREQ 1000000U |
||||||
|
|
||||||
|
#define DPS310__OSR_SE 3U |
||||||
|
|
||||||
|
// DPS310 has 10 milliseconds of spare time for each synchronous measurement / per second for asynchronous measurements
|
||||||
|
// this is for error prevention on friday-afternoon-products :D
|
||||||
|
// you can set it to 0 if you dare, but there is no warranty that it will still work
|
||||||
|
#define DPS310__BUSYTIME_FAILSAFE 10U |
||||||
|
#define DPS310__MAX_BUSYTIME ((1000U - DPS310__BUSYTIME_FAILSAFE) * DPS__BUSYTIME_SCALING) |
||||||
|
|
||||||
|
#define DPS310__REG_ADR_SPI3W 0x09U |
||||||
|
#define DPS310__REG_CONTENT_SPI3W 0x01U |
||||||
|
|
||||||
|
/////////// DPS422 ///////////
|
||||||
|
#define DPS422__PROD_ID 0x0A |
||||||
|
|
||||||
|
/////////// common ///////////
|
||||||
|
|
||||||
|
// slave address same for 422 and 310 (to be proved for future sensors)
|
||||||
|
#define DPS__FIFO_SIZE 32 |
||||||
|
#define DPS__STD_SLAVE_ADDRESS 0x77U |
||||||
|
#define DPS__RESULT_BLOCK_LENGTH 3 |
||||||
|
#define NUM_OF_COMMON_REGMASKS 16 |
||||||
|
|
||||||
|
#define DPS__MEASUREMENT_RATE_1 0 |
||||||
|
#define DPS__MEASUREMENT_RATE_2 1 |
||||||
|
#define DPS__MEASUREMENT_RATE_4 2 |
||||||
|
#define DPS__MEASUREMENT_RATE_8 3 |
||||||
|
#define DPS__MEASUREMENT_RATE_16 4 |
||||||
|
#define DPS__MEASUREMENT_RATE_32 5 |
||||||
|
#define DPS__MEASUREMENT_RATE_64 6 |
||||||
|
#define DPS__MEASUREMENT_RATE_128 7 |
||||||
|
|
||||||
|
#define DPS__OVERSAMPLING_RATE_1 DPS__MEASUREMENT_RATE_1 |
||||||
|
#define DPS__OVERSAMPLING_RATE_2 DPS__MEASUREMENT_RATE_2 |
||||||
|
#define DPS__OVERSAMPLING_RATE_4 DPS__MEASUREMENT_RATE_4 |
||||||
|
#define DPS__OVERSAMPLING_RATE_8 DPS__MEASUREMENT_RATE_8 |
||||||
|
#define DPS__OVERSAMPLING_RATE_16 DPS__MEASUREMENT_RATE_16 |
||||||
|
#define DPS__OVERSAMPLING_RATE_32 DPS__MEASUREMENT_RATE_32 |
||||||
|
#define DPS__OVERSAMPLING_RATE_64 DPS__MEASUREMENT_RATE_64 |
||||||
|
#define DPS__OVERSAMPLING_RATE_128 DPS__MEASUREMENT_RATE_128 |
||||||
|
|
||||||
|
//we use 0.1 ms units for time calculations, so 10 units are one millisecond
|
||||||
|
#define DPS__BUSYTIME_SCALING 10U |
||||||
|
|
||||||
|
#define DPS__NUM_OF_SCAL_FACTS 8 |
||||||
|
|
||||||
|
// status code
|
||||||
|
#define DPS__SUCCEEDED 0 |
||||||
|
#define DPS__FAIL_UNKNOWN -1 |
||||||
|
#define DPS__FAIL_INIT_FAILED -2 |
||||||
|
#define DPS__FAIL_TOOBUSY -3 |
||||||
|
#define DPS__FAIL_UNFINISHED -4 |
||||||
|
|
||||||
|
namespace dps |
||||||
|
{ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Operating mode. |
||||||
|
*
|
||||||
|
*/ |
||||||
|
enum Mode |
||||||
|
{ |
||||||
|
IDLE = 0x00, |
||||||
|
CMD_PRS = 0x01, |
||||||
|
CMD_TEMP = 0x02, |
||||||
|
CMD_BOTH = 0x03, // only for DPS422
|
||||||
|
CONT_PRS = 0x05, |
||||||
|
CONT_TMP = 0x06, |
||||||
|
CONT_BOTH = 0x07 |
||||||
|
}; |
||||||
|
|
||||||
|
enum RegisterBlocks_e |
||||||
|
{ |
||||||
|
PRS = 0, // pressure value
|
||||||
|
TEMP, // temperature value
|
||||||
|
}; |
||||||
|
|
||||||
|
const RegBlock_t registerBlocks[2] = { |
||||||
|
{0x00, 3}, |
||||||
|
{0x03, 3}, |
||||||
|
}; |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief registers for configuration and flags; these are the same for both 310 and 422, might need to be adapted for future sensors |
||||||
|
*
|
||||||
|
*/ |
||||||
|
enum Config_Registers_e |
||||||
|
{ |
||||||
|
TEMP_MR = 0, // temperature measure rate
|
||||||
|
TEMP_OSR, // temperature measurement resolution
|
||||||
|
PRS_MR, // pressure measure rate
|
||||||
|
PRS_OSR, // pressure measurement resolution
|
||||||
|
MSR_CTRL, // measurement control
|
||||||
|
FIFO_EN, |
||||||
|
|
||||||
|
TEMP_RDY, |
||||||
|
PRS_RDY, |
||||||
|
INT_FLAG_FIFO, |
||||||
|
INT_FLAG_TEMP, |
||||||
|
INT_FLAG_PRS, |
||||||
|
}; |
||||||
|
|
||||||
|
const RegMask_t config_registers[NUM_OF_COMMON_REGMASKS] = { |
||||||
|
{0x07, 0x70, 4}, // TEMP_MR
|
||||||
|
{0x07, 0x07, 0}, // TEMP_OSR
|
||||||
|
{0x06, 0x70, 4}, // PRS_MR
|
||||||
|
{0x06, 0x07, 0}, // PRS_OSR
|
||||||
|
{0x08, 0x07, 0}, // MSR_CTRL
|
||||||
|
{0x09, 0x02, 1}, // FIFO_EN
|
||||||
|
|
||||||
|
{0x08, 0x20, 5}, // TEMP_RDY
|
||||||
|
{0x08, 0x10, 4}, // PRS_RDY
|
||||||
|
{0x0A, 0x04, 2}, // INT_FLAG_FIFO
|
||||||
|
{0x0A, 0x02, 1}, // INT_FLAG_TEMP
|
||||||
|
{0x0A, 0x01, 0}, // INT_FLAG_PRS
|
||||||
|
}; |
||||||
|
|
||||||
|
} // namespace dps
|
||||||
|
#endif /* DPS_CONSTS_H_ */ |
Loading…
Reference in new issue