first fully functional integration (experimental)

This commit is contained in:
Klaus K Wilting 2018-12-27 17:09:40 +01:00
parent eb5dac2dea
commit 76600a86b1
10 changed files with 488 additions and 446 deletions

View File

@ -89,6 +89,7 @@ extern uint8_t volatile channel; // wifi channel rotation counter
extern uint16_t volatile macs_total, macs_wifi, macs_ble, extern uint16_t volatile macs_total, macs_wifi, macs_ble,
batt_voltage; // display values batt_voltage; // display values
extern hw_timer_t *channelSwitch, *sendCycle, *displaytimer; extern hw_timer_t *channelSwitch, *sendCycle, *displaytimer;
extern SemaphoreHandle_t I2Caccess;
extern std::set<uint16_t, std::less<uint16_t>, Mallocator<uint16_t>> macs; extern std::set<uint16_t, std::less<uint16_t>, Mallocator<uint16_t>> macs;
extern std::array<uint64_t, 0xff>::iterator it; extern std::array<uint64_t, 0xff>::iterator it;

View File

@ -103,7 +103,7 @@
/** BME680 configuration macros */ /** BME680 configuration macros */
/** Enable or un-comment the macro to provide floating point data output */ /** Enable or un-comment the macro to provide floating point data output */
#ifndef BME680_FLOAT_POINT_COMPENSATION #ifndef BME680_FLOAT_POINT_COMPENSATION
/* #define BME680_FLOAT_POINT_COMPENSATION */ //#define BME680_FLOAT_POINT_COMPENSATION
#endif #endif
/** BME680 General config */ /** BME680 General config */

View File

@ -47,186 +47,185 @@
#include "bsec.h" #include "bsec.h"
TwoWire* Bsec::wireObj = NULL; TwoWire *Bsec::wireObj = NULL;
SPIClass* Bsec::spiObj = NULL; SPIClass *Bsec::spiObj = NULL;
/** /**
* @brief Constructor * @brief Constructor
*/ */
Bsec::Bsec() Bsec::Bsec() {
{ nextCall = 0;
nextCall = 0; version.major = 0;
version.major = 0; version.minor = 0;
version.minor = 0; version.major_bugfix = 0;
version.major_bugfix = 0; version.minor_bugfix = 0;
version.minor_bugfix = 0; millisOverflowCounter = 0;
millisOverflowCounter = 0; lastTime = 0;
lastTime = 0; bme680Status = BME680_OK;
bme680Status = BME680_OK; outputTimestamp = 0;
outputTimestamp = 0; _tempOffset = 0.0f;
_tempOffset = 0.0f; status = BSEC_OK;
status = BSEC_OK; zeroOutputs();
zeroOutputs();
} }
/** /**
* @brief Function to initialize the BSEC library and the BME680 sensor * @brief Function to initialize the BSEC library and the BME680 sensor
*/ */
void Bsec::begin(uint8_t devId, enum bme680_intf intf, bme680_com_fptr_t read, bme680_com_fptr_t write, bme680_delay_fptr_t idleTask) void Bsec::begin(uint8_t devId, enum bme680_intf intf, bme680_com_fptr_t read,
{ bme680_com_fptr_t write, bme680_delay_fptr_t idleTask) {
_bme680.dev_id = devId; _bme680.dev_id = devId;
_bme680.intf = intf; _bme680.intf = intf;
_bme680.read = read; _bme680.read = read;
_bme680.write = write; _bme680.write = write;
_bme680.delay_ms = idleTask; _bme680.delay_ms = idleTask;
_bme680.amb_temp = 25; _bme680.amb_temp = 25;
_bme680.power_mode = BME680_FORCED_MODE; _bme680.power_mode = BME680_FORCED_MODE;
beginCommon(); beginCommon();
} }
/** /**
* @brief Function to initialize the BSEC library and the BME680 sensor * @brief Function to initialize the BSEC library and the BME680 sensor
*/ */
void Bsec::begin(uint8_t i2cAddr, TwoWire &i2c) void Bsec::begin(uint8_t i2cAddr, TwoWire &i2c) {
{ _bme680.dev_id = i2cAddr;
_bme680.dev_id = i2cAddr; _bme680.intf = BME680_I2C_INTF;
_bme680.intf = BME680_I2C_INTF; _bme680.read = Bsec::i2cRead;
_bme680.read = Bsec::i2cRead; _bme680.write = Bsec::i2cWrite;
_bme680.write = Bsec::i2cWrite; _bme680.delay_ms = Bsec::delay_ms;
_bme680.delay_ms = Bsec::delay_ms; _bme680.amb_temp = 25;
_bme680.amb_temp = 25; _bme680.power_mode = BME680_FORCED_MODE;
_bme680.power_mode = BME680_FORCED_MODE;
Bsec::wireObj = &i2c; Bsec::wireObj = &i2c;
Bsec::wireObj->begin(); Bsec::wireObj->begin();
beginCommon(); beginCommon();
} }
/** /**
* @brief Function to initialize the BSEC library and the BME680 sensor * @brief Function to initialize the BSEC library and the BME680 sensor
*/ */
void Bsec::begin(uint8_t chipSelect, SPIClass &spi) void Bsec::begin(uint8_t chipSelect, SPIClass &spi) {
{ _bme680.dev_id = chipSelect;
_bme680.dev_id = chipSelect; _bme680.intf = BME680_SPI_INTF;
_bme680.intf = BME680_SPI_INTF; _bme680.read = Bsec::spiTransfer;
_bme680.read = Bsec::spiTransfer; _bme680.write = Bsec::spiTransfer;
_bme680.write = Bsec::spiTransfer; _bme680.delay_ms = Bsec::delay_ms;
_bme680.delay_ms = Bsec::delay_ms; _bme680.amb_temp = 25;
_bme680.amb_temp = 25; _bme680.power_mode = BME680_FORCED_MODE;
_bme680.power_mode = BME680_FORCED_MODE;
pinMode(chipSelect, OUTPUT); pinMode(chipSelect, OUTPUT);
digitalWrite(chipSelect, HIGH); digitalWrite(chipSelect, HIGH);
Bsec::spiObj = &spi; Bsec::spiObj = &spi;
Bsec::spiObj->begin(); Bsec::spiObj->begin();
beginCommon(); beginCommon();
} }
/** /**
* @brief Common code for the begin function * @brief Common code for the begin function
*/ */
void Bsec::beginCommon(void) void Bsec::beginCommon(void) {
{ status = bsec_init();
status = bsec_init();
getVersion(); getVersion();
bme680Status = bme680_init(&_bme680); bme680Status = bme680_init(&_bme680);
} }
/** /**
* @brief Function that sets the desired sensors and the sample rates * @brief Function that sets the desired sensors and the sample rates
*/ */
void Bsec::updateSubscription(bsec_virtual_sensor_t sensorList[], uint8_t nSensors, float sampleRate) void Bsec::updateSubscription(bsec_virtual_sensor_t sensorList[],
{ uint8_t nSensors, float sampleRate) {
bsec_sensor_configuration_t virtualSensors[BSEC_NUMBER_OUTPUTS], bsec_sensor_configuration_t virtualSensors[BSEC_NUMBER_OUTPUTS],
sensorSettings[BSEC_MAX_PHYSICAL_SENSOR]; sensorSettings[BSEC_MAX_PHYSICAL_SENSOR];
uint8_t nVirtualSensors = 0, nSensorSettings = BSEC_MAX_PHYSICAL_SENSOR; uint8_t nVirtualSensors = 0, nSensorSettings = BSEC_MAX_PHYSICAL_SENSOR;
for (uint8_t i = 0; i < nSensors; i++) { for (uint8_t i = 0; i < nSensors; i++) {
virtualSensors[nVirtualSensors].sensor_id = sensorList[i]; virtualSensors[nVirtualSensors].sensor_id = sensorList[i];
virtualSensors[nVirtualSensors].sample_rate = sampleRate; virtualSensors[nVirtualSensors].sample_rate = sampleRate;
nVirtualSensors++; nVirtualSensors++;
} }
status = bsec_update_subscription(virtualSensors, nVirtualSensors, sensorSettings, &nSensorSettings); status = bsec_update_subscription(virtualSensors, nVirtualSensors,
return; sensorSettings, &nSensorSettings);
return;
} }
/** /**
* @brief Callback from the user to trigger reading of data from the BME680, process and store outputs * @brief Callback from the user to trigger reading of data from the BME680,
* process and store outputs
*/ */
bool Bsec::run(void) bool Bsec::run(void) {
{ bool newData = false;
bool newData = false; /* Check if the time has arrived to call do_steps() */
/* Check if the time has arrived to call do_steps() */ int64_t callTimeMs = getTimeMs();
int64_t callTimeMs = getTimeMs();
if (callTimeMs >= nextCall) { if (callTimeMs >= nextCall) {
bsec_bme_settings_t bme680Settings; bsec_bme_settings_t bme680Settings;
int64_t callTimeNs = callTimeMs * INT64_C(1000000); int64_t callTimeNs = callTimeMs * INT64_C(1000000);
status = bsec_sensor_control(callTimeNs, &bme680Settings); status = bsec_sensor_control(callTimeNs, &bme680Settings);
if (status < BSEC_OK) if (status < BSEC_OK)
return false; return false;
nextCall = bme680Settings.next_call / INT64_C(1000000); // Convert from ns to ms nextCall =
bme680Settings.next_call / INT64_C(1000000); // Convert from ns to ms
bme680Status = setBme680Config(bme680Settings); bme680Status = setBme680Config(bme680Settings);
if (bme680Status != BME680_OK) { if (bme680Status != BME680_OK) {
return false; return false;
} }
bme680Status = bme680_set_sensor_mode(&_bme680); bme680Status = bme680_set_sensor_mode(&_bme680);
if (bme680Status != BME680_OK) { if (bme680Status != BME680_OK) {
return false; return false;
} }
/* Wait for measurement to complete */ /* Wait for measurement to complete */
uint16_t meas_dur = 0; uint16_t meas_dur = 0;
bme680_get_profile_dur(&meas_dur, &_bme680); bme680_get_profile_dur(&meas_dur, &_bme680);
delay_ms(meas_dur); delay_ms(meas_dur);
newData = readProcessData(callTimeNs, bme680Settings); newData = readProcessData(callTimeNs, bme680Settings);
} }
return newData; return newData;
} }
/** /**
* @brief Function to get the state of the algorithm to save to non-volatile memory * @brief Function to get the state of the algorithm to save to non-volatile
* memory
*/ */
void Bsec::getState(uint8_t *state) void Bsec::getState(uint8_t *state) {
{ uint8_t workBuffer[BSEC_MAX_STATE_BLOB_SIZE];
uint8_t workBuffer[BSEC_MAX_STATE_BLOB_SIZE]; uint32_t n_serialized_state = BSEC_MAX_STATE_BLOB_SIZE;
uint32_t n_serialized_state = BSEC_MAX_STATE_BLOB_SIZE; status = bsec_get_state(0, state, BSEC_MAX_STATE_BLOB_SIZE, workBuffer,
status = bsec_get_state(0, state, BSEC_MAX_STATE_BLOB_SIZE, workBuffer, BSEC_MAX_STATE_BLOB_SIZE, &n_serialized_state); BSEC_MAX_STATE_BLOB_SIZE, &n_serialized_state);
} }
/** /**
* @brief Function to set the state of the algorithm from non-volatile memory * @brief Function to set the state of the algorithm from non-volatile memory
*/ */
void Bsec::setState(uint8_t *state) void Bsec::setState(uint8_t *state) {
{ uint8_t workBuffer[BSEC_MAX_STATE_BLOB_SIZE];
uint8_t workBuffer[BSEC_MAX_STATE_BLOB_SIZE];
status = bsec_set_state(state, BSEC_MAX_STATE_BLOB_SIZE, workBuffer, BSEC_MAX_STATE_BLOB_SIZE); status = bsec_set_state(state, BSEC_MAX_STATE_BLOB_SIZE, workBuffer,
BSEC_MAX_STATE_BLOB_SIZE);
} }
/** /**
* @brief Function to set the configuration of the algorithm from memory * @brief Function to set the configuration of the algorithm from memory
*/ */
void Bsec::setConfig(const uint8_t *state) void Bsec::setConfig(const uint8_t *state) {
{ uint8_t workBuffer[BSEC_MAX_PROPERTY_BLOB_SIZE];
uint8_t workBuffer[BSEC_MAX_PROPERTY_BLOB_SIZE];
status = bsec_set_configuration(state, BSEC_MAX_PROPERTY_BLOB_SIZE, workBuffer, sizeof(workBuffer)); status = bsec_set_configuration(state, BSEC_MAX_PROPERTY_BLOB_SIZE,
workBuffer, sizeof(workBuffer));
} }
/* Private functions */ /* Private functions */
@ -234,260 +233,266 @@ void Bsec::setConfig(const uint8_t *state)
/** /**
* @brief Get the version of the BSEC library * @brief Get the version of the BSEC library
*/ */
void Bsec::getVersion(void) void Bsec::getVersion(void) { bsec_get_version(&version); }
{
bsec_get_version(&version);
}
/** /**
* @brief Read data from the BME680 and process it * @brief Read data from the BME680 and process it
*/ */
bool Bsec::readProcessData(int64_t currTimeNs, bsec_bme_settings_t bme680Settings) bool Bsec::readProcessData(int64_t currTimeNs,
{ bsec_bme_settings_t bme680Settings) {
bme680Status = bme680_get_sensor_data(&_data, &_bme680); bme680Status = bme680_get_sensor_data(&_data, &_bme680);
if (bme680Status != BME680_OK) { if (bme680Status != BME680_OK) {
return false; return false;
} }
bsec_input_t inputs[BSEC_MAX_PHYSICAL_SENSOR]; // Temp, Pres, Hum & Gas bsec_input_t inputs[BSEC_MAX_PHYSICAL_SENSOR]; // Temp, Pres, Hum & Gas
uint8_t nInputs = 0, nOutputs = 0; uint8_t nInputs = 0, nOutputs = 0;
if (_data.status & BME680_NEW_DATA_MSK) { if (_data.status & BME680_NEW_DATA_MSK) {
if (bme680Settings.process_data & BSEC_PROCESS_TEMPERATURE) { if (bme680Settings.process_data & BSEC_PROCESS_TEMPERATURE) {
inputs[nInputs].sensor_id = BSEC_INPUT_TEMPERATURE; inputs[nInputs].sensor_id = BSEC_INPUT_TEMPERATURE;
inputs[nInputs].signal = _data.temperature; #ifdef BME680_FLOAT_POINT_COMPENSATION
inputs[nInputs].time_stamp = currTimeNs; inputs[nInputs].signal = _data.temperature;
nInputs++; #else
/* Temperature offset from the real temperature due to external heat sources */ inputs[nInputs].signal = _data.temperature / 100.0f;
inputs[nInputs].sensor_id = BSEC_INPUT_HEATSOURCE; #endif
inputs[nInputs].signal = _tempOffset; inputs[nInputs].time_stamp = currTimeNs;
inputs[nInputs].time_stamp = currTimeNs; nInputs++;
nInputs++; /* Temperature offset from the real temperature due to external heat
} * sources */
if (bme680Settings.process_data & BSEC_PROCESS_HUMIDITY) { inputs[nInputs].sensor_id = BSEC_INPUT_HEATSOURCE;
inputs[nInputs].sensor_id = BSEC_INPUT_HUMIDITY; inputs[nInputs].signal = _tempOffset;
inputs[nInputs].signal = _data.humidity; inputs[nInputs].time_stamp = currTimeNs;
inputs[nInputs].time_stamp = currTimeNs; nInputs++;
nInputs++; }
} if (bme680Settings.process_data & BSEC_PROCESS_HUMIDITY) {
if (bme680Settings.process_data & BSEC_PROCESS_PRESSURE) { inputs[nInputs].sensor_id = BSEC_INPUT_HUMIDITY;
inputs[nInputs].sensor_id = BSEC_INPUT_PRESSURE; #ifdef BME680_FLOAT_POINT_COMPENSATION
inputs[nInputs].signal = _data.pressure; inputs[nInputs].signal = _data.humidity;
inputs[nInputs].time_stamp = currTimeNs; #else
nInputs++; inputs[nInputs].signal = _data.humidity / 1000.0f;
} #endif
if (bme680Settings.process_data & BSEC_PROCESS_GAS) { inputs[nInputs].time_stamp = currTimeNs;
inputs[nInputs].sensor_id = BSEC_INPUT_GASRESISTOR; nInputs++;
inputs[nInputs].signal = _data.gas_resistance; }
inputs[nInputs].time_stamp = currTimeNs; if (bme680Settings.process_data & BSEC_PROCESS_PRESSURE) {
nInputs++; inputs[nInputs].sensor_id = BSEC_INPUT_PRESSURE;
} inputs[nInputs].signal = _data.pressure;
} inputs[nInputs].time_stamp = currTimeNs;
nInputs++;
}
if (bme680Settings.process_data & BSEC_PROCESS_GAS) {
inputs[nInputs].sensor_id = BSEC_INPUT_GASRESISTOR;
inputs[nInputs].signal = _data.gas_resistance;
inputs[nInputs].time_stamp = currTimeNs;
nInputs++;
}
}
if (nInputs > 0) { if (nInputs > 0) {
nOutputs = BSEC_NUMBER_OUTPUTS; nOutputs = BSEC_NUMBER_OUTPUTS;
bsec_output_t _outputs[BSEC_NUMBER_OUTPUTS]; bsec_output_t _outputs[BSEC_NUMBER_OUTPUTS];
status = bsec_do_steps(inputs, nInputs, _outputs, &nOutputs); status = bsec_do_steps(inputs, nInputs, _outputs, &nOutputs);
if (status != BSEC_OK) if (status != BSEC_OK)
return false; return false;
zeroOutputs(); zeroOutputs();
if (nOutputs > 0) { if (nOutputs > 0) {
outputTimestamp = _outputs[0].time_stamp / 1000000; // Convert from ns to ms outputTimestamp =
_outputs[0].time_stamp / 1000000; // Convert from ns to ms
for (uint8_t i = 0; i < nOutputs; i++) { for (uint8_t i = 0; i < nOutputs; i++) {
switch (_outputs[i].sensor_id) { switch (_outputs[i].sensor_id) {
case BSEC_OUTPUT_IAQ: case BSEC_OUTPUT_IAQ:
iaqEstimate = _outputs[i].signal; iaqEstimate = _outputs[i].signal;
iaqAccuracy = _outputs[i].accuracy; iaqAccuracy = _outputs[i].accuracy;
break; break;
case BSEC_OUTPUT_STATIC_IAQ: case BSEC_OUTPUT_STATIC_IAQ:
staticIaq = _outputs[i].signal; staticIaq = _outputs[i].signal;
staticIaqAccuracy = _outputs[i].accuracy; staticIaqAccuracy = _outputs[i].accuracy;
break; break;
case BSEC_OUTPUT_CO2_EQUIVALENT: case BSEC_OUTPUT_CO2_EQUIVALENT:
co2Equivalent = _outputs[i].signal; co2Equivalent = _outputs[i].signal;
co2Accuracy = _outputs[i].accuracy; co2Accuracy = _outputs[i].accuracy;
break; break;
case BSEC_OUTPUT_BREATH_VOC_EQUIVALENT: case BSEC_OUTPUT_BREATH_VOC_EQUIVALENT:
breathVocEquivalent = _outputs[i].signal; breathVocEquivalent = _outputs[i].signal;
breathVocAccuracy = _outputs[i].accuracy; breathVocAccuracy = _outputs[i].accuracy;
break; break;
case BSEC_OUTPUT_RAW_TEMPERATURE: case BSEC_OUTPUT_RAW_TEMPERATURE:
rawTemperature = _outputs[i].signal; rawTemperature = _outputs[i].signal;
break; break;
case BSEC_OUTPUT_RAW_PRESSURE: case BSEC_OUTPUT_RAW_PRESSURE:
pressure = _outputs[i].signal; pressure = _outputs[i].signal;
break; break;
case BSEC_OUTPUT_RAW_HUMIDITY: case BSEC_OUTPUT_RAW_HUMIDITY:
rawHumidity = _outputs[i].signal; rawHumidity = _outputs[i].signal;
break; break;
case BSEC_OUTPUT_RAW_GAS: case BSEC_OUTPUT_RAW_GAS:
gasResistance = _outputs[i].signal; gasResistance = _outputs[i].signal;
break; break;
case BSEC_OUTPUT_STABILIZATION_STATUS: case BSEC_OUTPUT_STABILIZATION_STATUS:
stabStatus = _outputs[i].signal; stabStatus = _outputs[i].signal;
break; break;
case BSEC_OUTPUT_RUN_IN_STATUS: case BSEC_OUTPUT_RUN_IN_STATUS:
runInStatus = _outputs[i].signal; runInStatus = _outputs[i].signal;
break; break;
case BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE: case BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE:
temperature = _outputs[i].signal; temperature = _outputs[i].signal;
break; break;
case BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY: case BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY:
humidity = _outputs[i].signal; humidity = _outputs[i].signal;
break; break;
case BSEC_OUTPUT_COMPENSATED_GAS: case BSEC_OUTPUT_COMPENSATED_GAS:
compGasValue = _outputs[i].signal; compGasValue = _outputs[i].signal;
compGasAccuracy = _outputs[i].accuracy; compGasAccuracy = _outputs[i].accuracy;
break; break;
case BSEC_OUTPUT_GAS_PERCENTAGE: case BSEC_OUTPUT_GAS_PERCENTAGE:
gasPercentage = _outputs[i].signal; gasPercentage = _outputs[i].signal;
gasPercentageAcccuracy = _outputs[i].accuracy; gasPercentageAcccuracy = _outputs[i].accuracy;
break; break;
default: default:
break; break;
} }
} }
return true; return true;
} }
} }
return false; return false;
} }
/** /**
* @brief Set the BME680 sensor's configuration * @brief Set the BME680 sensor's configuration
*/ */
int8_t Bsec::setBme680Config(bsec_bme_settings_t bme680Settings) int8_t Bsec::setBme680Config(bsec_bme_settings_t bme680Settings) {
{ _bme680.gas_sett.run_gas = bme680Settings.run_gas;
_bme680.gas_sett.run_gas = bme680Settings.run_gas; _bme680.tph_sett.os_hum = bme680Settings.humidity_oversampling;
_bme680.tph_sett.os_hum = bme680Settings.humidity_oversampling; _bme680.tph_sett.os_temp = bme680Settings.temperature_oversampling;
_bme680.tph_sett.os_temp = bme680Settings.temperature_oversampling; _bme680.tph_sett.os_pres = bme680Settings.pressure_oversampling;
_bme680.tph_sett.os_pres = bme680Settings.pressure_oversampling; _bme680.gas_sett.heatr_temp = bme680Settings.heater_temperature;
_bme680.gas_sett.heatr_temp = bme680Settings.heater_temperature; _bme680.gas_sett.heatr_dur = bme680Settings.heating_duration;
_bme680.gas_sett.heatr_dur = bme680Settings.heating_duration; uint16_t desired_settings = BME680_OST_SEL | BME680_OSP_SEL | BME680_OSH_SEL |
uint16_t desired_settings = BME680_OST_SEL | BME680_OSP_SEL | BME680_OSH_SEL | BME680_FILTER_SEL BME680_FILTER_SEL | BME680_GAS_SENSOR_SEL;
| BME680_GAS_SENSOR_SEL; return bme680_set_sensor_settings(desired_settings, &_bme680);
return bme680_set_sensor_settings(desired_settings, &_bme680);
} }
/** /**
* @brief Function to zero the outputs * @brief Function to zero the outputs
*/ */
void Bsec::zeroOutputs(void) void Bsec::zeroOutputs(void) {
{ temperature = 0.0f;
temperature = 0.0f; pressure = 0.0f;
pressure = 0.0f; humidity = 0.0f;
humidity = 0.0f; gasResistance = 0.0f;
gasResistance = 0.0f; rawTemperature = 0.0f;
rawTemperature = 0.0f; rawHumidity = 0.0f;
rawHumidity = 0.0f; stabStatus = 0.0f;
stabStatus = 0.0f; runInStatus = 0.0f;
runInStatus = 0.0f; iaqEstimate = 0.0f;
iaqEstimate = 0.0f; iaqAccuracy = 0;
iaqAccuracy = 0; staticIaq = 0.0f;
staticIaq = 0.0f; staticIaqAccuracy = 0;
staticIaqAccuracy = 0; co2Equivalent = 0.0f;
co2Equivalent = 0.0f; co2Accuracy = 0;
co2Accuracy = 0; breathVocEquivalent = 0.0f;
breathVocEquivalent = 0.0f; breathVocAccuracy = 0;
breathVocAccuracy = 0; compGasValue = 0.0f;
compGasValue = 0.0f; compGasAccuracy = 0;
compGasAccuracy = 0; gasPercentage = 0.0f;
gasPercentage = 0.0f; gasPercentageAcccuracy = 0;
gasPercentageAcccuracy = 0;
} }
/** /**
* @brief Function to calculate an int64_t timestamp in milliseconds * @brief Function to calculate an int64_t timestamp in milliseconds
*/ */
int64_t Bsec::getTimeMs(void) int64_t Bsec::getTimeMs(void) {
{ int64_t timeMs = millis();
int64_t timeMs = millis();
if (lastTime > timeMs) { // An overflow occured if (lastTime > timeMs) { // An overflow occured
lastTime = timeMs; lastTime = timeMs;
millisOverflowCounter++; millisOverflowCounter++;
} }
return timeMs + (millisOverflowCounter * 0xFFFFFFFF); return timeMs + (millisOverflowCounter * 0xFFFFFFFF);
} }
/** /**
@brief Task that delays for a ms period of time @brief Task that delays for a ms period of time
*/ */
void Bsec::delay_ms(uint32_t period) void Bsec::delay_ms(uint32_t period) {
{ // Wait for a period amount of ms
// Wait for a period amount of ms // The system may simply idle, sleep or even perform background tasks
// The system may simply idle, sleep or even perform background tasks delay(period);
delay(period);
} }
/** /**
@brief Callback function for reading registers over I2C @brief Callback function for reading registers over I2C
*/ */
int8_t Bsec::i2cRead(uint8_t devId, uint8_t regAddr, uint8_t *regData, uint16_t length) int8_t Bsec::i2cRead(uint8_t devId, uint8_t regAddr, uint8_t *regData,
{ uint16_t length) {
uint16_t i; uint16_t i;
int8_t rslt = 0; int8_t rslt = 0;
if(Bsec::wireObj) { if (Bsec::wireObj) {
Bsec::wireObj->beginTransmission(devId); Bsec::wireObj->beginTransmission(devId);
Bsec::wireObj->write(regAddr); Bsec::wireObj->write(regAddr);
rslt = Bsec::wireObj->endTransmission(); rslt = Bsec::wireObj->endTransmission();
Bsec::wireObj->requestFrom((int) devId, (int) length); Bsec::wireObj->requestFrom((int)devId, (int)length);
for (i = 0; (i < length) && Bsec::wireObj->available(); i++) { for (i = 0; (i < length) && Bsec::wireObj->available(); i++) {
regData[i] = Bsec::wireObj->read(); regData[i] = Bsec::wireObj->read();
} }
} else { } else {
rslt = -1; rslt = -1;
} }
return rslt; return rslt;
} }
/** /**
* @brief Callback function for writing registers over I2C * @brief Callback function for writing registers over I2C
*/ */
int8_t Bsec::i2cWrite(uint8_t devId, uint8_t regAddr, uint8_t *regData, uint16_t length) int8_t Bsec::i2cWrite(uint8_t devId, uint8_t regAddr, uint8_t *regData,
{ uint16_t length) {
uint16_t i; uint16_t i;
int8_t rslt = 0; int8_t rslt = 0;
if(Bsec::wireObj) { if (Bsec::wireObj) {
Bsec::wireObj->beginTransmission(devId); Bsec::wireObj->beginTransmission(devId);
Bsec::wireObj->write(regAddr); Bsec::wireObj->write(regAddr);
for (i = 0; i < length; i++) { for (i = 0; i < length; i++) {
Bsec::wireObj->write(regData[i]); Bsec::wireObj->write(regData[i]);
} }
rslt = Bsec::wireObj->endTransmission(); rslt = Bsec::wireObj->endTransmission();
} else { } else {
rslt = -1; rslt = -1;
} }
return rslt; return rslt;
} }
/** /**
* @brief Callback function for reading and writing registers over SPI * @brief Callback function for reading and writing registers over SPI
*/ */
int8_t Bsec::spiTransfer(uint8_t devId, uint8_t regAddr, uint8_t *regData, uint16_t length) int8_t Bsec::spiTransfer(uint8_t devId, uint8_t regAddr, uint8_t *regData,
{ uint16_t length) {
int8_t rslt = 0; int8_t rslt = 0;
if(Bsec::spiObj) { if (Bsec::spiObj) {
Bsec::spiObj->beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0)); // Can be upto 10MHz Bsec::spiObj->beginTransaction(
SPISettings(4000000, MSBFIRST, SPI_MODE0)); // Can be upto 10MHz
digitalWrite(devId, LOW); digitalWrite(devId, LOW);
Bsec::spiObj->transfer(regAddr); // Write the register address, ignore the return Bsec::spiObj->transfer(
for (uint16_t i = 0; i < length; i++) regAddr); // Write the register address, ignore the return
regData[i] = Bsec::spiObj->transfer(regData[i]); for (uint16_t i = 0; i < length; i++)
regData[i] = Bsec::spiObj->transfer(regData[i]);
digitalWrite(devId, HIGH); digitalWrite(devId, HIGH);
Bsec::spiObj->endTransaction(); Bsec::spiObj->endTransaction();
} else { } else {
rslt = -1; rslt = -1;
} }
return rslt;; return rslt;
;
} }

View File

@ -33,7 +33,7 @@ description = Paxcounter is a proof-of-concept ESP32 device for metering passeng
release_version = 1.7.03 release_version = 1.7.03
; DEBUG LEVEL: For production run set to 0, otherwise device will leak RAM while running! ; DEBUG LEVEL: For production run set to 0, otherwise device will leak RAM while running!
; 0=None, 1=Error, 2=Warn, 3=Info, 4=Debug, 5=Verbose ; 0=None, 1=Error, 2=Warn, 3=Info, 4=Debug, 5=Verbose
debug_level = 4 debug_level = 3
; UPLOAD MODE: select esptool to flash via USB/UART, select custom to upload to cloud for OTA ; UPLOAD MODE: select esptool to flash via USB/UART, select custom to upload to cloud for OTA
upload_protocol = esptool upload_protocol = esptool
;upload_protocol = custom ;upload_protocol = custom

View File

@ -7,60 +7,63 @@ static const char TAG[] = "main";
bmeStatus_t bme_status; bmeStatus_t bme_status;
TaskHandle_t BmeTask; TaskHandle_t BmeTask;
float bme_offset = (float)BME_TEMP_OFFSET;
Bsec iaqSensor; Bsec iaqSensor;
bsec_virtual_sensor_t sensorList[10] = {
BSEC_OUTPUT_RAW_TEMPERATURE,
BSEC_OUTPUT_RAW_PRESSURE,
BSEC_OUTPUT_RAW_HUMIDITY,
BSEC_OUTPUT_RAW_GAS,
BSEC_OUTPUT_IAQ,
BSEC_OUTPUT_STATIC_IAQ,
BSEC_OUTPUT_CO2_EQUIVALENT,
BSEC_OUTPUT_BREATH_VOC_EQUIVALENT,
BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE,
BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY,
};
// initialize BME680 sensor // initialize BME680 sensor
int bme_init(void) { int bme_init(void) {
Wire.begin(HAS_BME); // block i2c bus access
iaqSensor.begin(BME_ADDR, Wire); if (xSemaphoreTake(I2Caccess, (DISPLAYREFRESH_MS / portTICK_PERIOD_MS)) ==
pdTRUE) {
ESP_LOGI(TAG, "BSEC v%d.%d.%d.%d", iaqSensor.version.major, Wire.begin(HAS_BME);
iaqSensor.version.minor, iaqSensor.version.major_bugfix, iaqSensor.begin(BME_ADDR, Wire);
iaqSensor.version.minor_bugfix);
iaqSensor.setConfig(bsec_config_iaq); ESP_LOGI(TAG, "BSEC v%d.%d.%d.%d", iaqSensor.version.major,
iaqSensor.version.minor, iaqSensor.version.major_bugfix,
iaqSensor.version.minor_bugfix);
if (checkIaqSensorStatus()) iaqSensor.setConfig(bsec_config_iaq);
ESP_LOGI(TAG, "BME680 sensor found and initialized");
else { if (checkIaqSensorStatus())
ESP_LOGE(TAG, "BME680 sensor not found"); ESP_LOGI(TAG, "BME680 sensor found and initialized");
else {
ESP_LOGE(TAG, "BME680 sensor not found");
return 1;
}
iaqSensor.setTemperatureOffset((float)BME_TEMP_OFFSET);
iaqSensor.updateSubscription(sensorList, 10, BSEC_SAMPLE_RATE_LP);
if (checkIaqSensorStatus())
ESP_LOGI(TAG, "BSEC subscription succesful");
else {
ESP_LOGE(TAG, "BSEC subscription error");
return 1;
}
xSemaphoreGive(I2Caccess); // release i2c bus access
} else {
ESP_LOGE(TAG, "I2c bus busy - BME680 initialization error");
return 1; return 1;
} }
bsec_virtual_sensor_t sensorList[10] = { } // bme_init()
BSEC_OUTPUT_RAW_TEMPERATURE,
BSEC_OUTPUT_RAW_PRESSURE,
BSEC_OUTPUT_RAW_HUMIDITY,
BSEC_OUTPUT_RAW_GAS,
BSEC_OUTPUT_IAQ,
BSEC_OUTPUT_STATIC_IAQ,
BSEC_OUTPUT_CO2_EQUIVALENT,
BSEC_OUTPUT_BREATH_VOC_EQUIVALENT,
BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE,
BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY,
};
iaqSensor.updateSubscription(sensorList, 10, BSEC_SAMPLE_RATE_LP);
if (checkIaqSensorStatus())
ESP_LOGI(TAG, "BSEC subscription succesful");
else {
ESP_LOGE(TAG, "BSEC subscription error");
return 1;
}
iaqSensor.setTemperatureOffset(bme_offset);
if (checkIaqSensorStatus())
ESP_LOGI(TAG, "Ttemperature offset initialized succesful");
else {
ESP_LOGE(TAG, "Temperature offset initialization error");
return 1;
}
}
// Helper function definitions // Helper function definitions
int checkIaqSensorStatus(void) { int checkIaqSensorStatus(void) {
@ -83,7 +86,7 @@ int checkIaqSensorStatus(void) {
} }
return rslt; return rslt;
} } // checkIaqSensorStatus()
// loop function which reads and processes data based on sensor settings // loop function which reads and processes data based on sensor settings
void bme_loop(void *pvParameters) { void bme_loop(void *pvParameters) {
@ -92,16 +95,24 @@ void bme_loop(void *pvParameters) {
#ifdef HAS_BME #ifdef HAS_BME
while (checkIaqSensorStatus()) { while (checkIaqSensorStatus()) {
if (iaqSensor.run()) { // If new data is available
bme_status.raw_temperature = iaqSensor.rawTemperature; // block i2c bus access
bme_status.raw_humidity = iaqSensor.rawHumidity; if (xSemaphoreTake(I2Caccess, (DISPLAYREFRESH_MS / portTICK_PERIOD_MS)) ==
bme_status.temperature = iaqSensor.temperature; pdTRUE) {
bme_status.humidity = iaqSensor.humidity;
bme_status.pressure = if (iaqSensor.run()) { // If new data is available
(iaqSensor.pressure / 100.0); // conversion Pa -> hPa bme_status.raw_temperature = iaqSensor.rawTemperature;
bme_status.iaq = iaqSensor.iaqEstimate; bme_status.raw_humidity = iaqSensor.rawHumidity;
bme_status.iaq_accuracy = iaqSensor.iaqAccuracy; bme_status.temperature = iaqSensor.temperature;
bme_status.gas = iaqSensor.gasResistance; bme_status.humidity = iaqSensor.humidity;
bme_status.pressure =
(iaqSensor.pressure / 100.0); // conversion Pa -> hPa
bme_status.iaq = iaqSensor.iaqEstimate;
bme_status.iaq_accuracy = iaqSensor.iaqAccuracy;
bme_status.gas = iaqSensor.gasResistance;
}
xSemaphoreGive(I2Caccess); // release i2c bus access
} }
} }
#endif #endif

View File

@ -52,7 +52,12 @@ void doHousekeeping() {
// read battery voltage into global variable // read battery voltage into global variable
#ifdef HAS_BATTERY_PROBE #ifdef HAS_BATTERY_PROBE
batt_voltage = read_voltage(); batt_voltage = read_voltage();
ESP_LOGI(TAG, "Measured Voltage: %dmV", batt_voltage); ESP_LOGI(TAG, "Voltage: %dmV", batt_voltage);
#endif
// display BME sensor data if present
#ifdef HAS_BME
ESP_LOGI(TAG, "BME680 Temp: %.2f°C | IAQ: %.2f", bme_status.temperature, bme_status.iaq);
#endif #endif
// check free heap memory // check free heap memory

View File

@ -98,96 +98,104 @@ void init_display(const char *Productname, const char *Version) {
void refreshtheDisplay() { void refreshtheDisplay() {
// set display on/off according to current device configuration // block i2c bus access
if (DisplayState != cfg.screenon) { if (xSemaphoreTake(I2Caccess, (DISPLAYREFRESH_MS / portTICK_PERIOD_MS)) ==
DisplayState = cfg.screenon; pdTRUE) {
u8x8.setPowerSave(!cfg.screenon);
}
// if display is switched off we don't refresh it and save time // set display on/off according to current device configuration
if (!DisplayState) if (DisplayState != cfg.screenon) {
return; DisplayState = cfg.screenon;
u8x8.setPowerSave(!cfg.screenon);
}
uint8_t msgWaiting; // if display is switched off we don't refresh it and save time
char buff[16]; // 16 chars line buffer if (!DisplayState)
return;
// update counter (lines 0-1) uint8_t msgWaiting;
snprintf( char buff[16]; // 16 chars line buffer
buff, sizeof(buff), "PAX:%-4d",
(int)macs.size()); // convert 16-bit MAC counter to decimal counter value // update counter (lines 0-1)
u8x8.draw2x2String(0, 0, snprintf(
buff); // display number on unique macs total Wifi + BLE buff, sizeof(buff), "PAX:%-4d",
(int)
macs.size()); // convert 16-bit MAC counter to decimal counter value
u8x8.draw2x2String(0, 0,
buff); // display number on unique macs total Wifi + BLE
// update Battery status (line 2) // update Battery status (line 2)
#ifdef HAS_BATTERY_PROBE #ifdef HAS_BATTERY_PROBE
u8x8.setCursor(0, 2); u8x8.setCursor(0, 2);
u8x8.printf("B:%.1fV", batt_voltage / 1000.0); u8x8.printf("B:%.1fV", batt_voltage / 1000.0);
#endif #endif
// update GPS status (line 2) // update GPS status (line 2)
#ifdef HAS_GPS #ifdef HAS_GPS
u8x8.setCursor(9, 2); u8x8.setCursor(9, 2);
if (!gps.location.isValid()) // if no fix then display Sats value inverse if (!gps.location.isValid()) // if no fix then display Sats value inverse
{ {
u8x8.setInverseFont(1); u8x8.setInverseFont(1);
u8x8.printf("Sats:%.2d", gps.satellites.value()); u8x8.printf("Sats:%.2d", gps.satellites.value());
u8x8.setInverseFont(0); u8x8.setInverseFont(0);
} else } else
u8x8.printf("Sats:%.2d", gps.satellites.value()); u8x8.printf("Sats:%.2d", gps.satellites.value());
#endif #endif
// update bluetooth counter + LoRa SF (line 3) // update bluetooth counter + LoRa SF (line 3)
#ifdef BLECOUNTER #ifdef BLECOUNTER
u8x8.setCursor(0, 3); u8x8.setCursor(0, 3);
if (cfg.blescan) if (cfg.blescan)
u8x8.printf("BLTH:%-4d", macs_ble); u8x8.printf("BLTH:%-4d", macs_ble);
else else
u8x8.printf("%s", "BLTH:off"); u8x8.printf("%s", "BLTH:off");
#endif #endif
#ifdef HAS_LORA #ifdef HAS_LORA
u8x8.setCursor(11, 3); u8x8.setCursor(11, 3);
u8x8.printf("SF:"); u8x8.printf("SF:");
if (cfg.adrmode) // if ADR=on then display SF value inverse if (cfg.adrmode) // if ADR=on then display SF value inverse
u8x8.setInverseFont(1); u8x8.setInverseFont(1);
u8x8.printf("%c%c", lora_datarate[LMIC.datarate * 2], u8x8.printf("%c%c", lora_datarate[LMIC.datarate * 2],
lora_datarate[LMIC.datarate * 2 + 1]); lora_datarate[LMIC.datarate * 2 + 1]);
if (cfg.adrmode) // switch off inverse if it was turned on if (cfg.adrmode) // switch off inverse if it was turned on
u8x8.setInverseFont(0); u8x8.setInverseFont(0);
#endif // HAS_LORA #endif // HAS_LORA
// update wifi counter + channel display (line 4) // update wifi counter + channel display (line 4)
u8x8.setCursor(0, 4); u8x8.setCursor(0, 4);
u8x8.printf("WIFI:%-4d", macs_wifi); u8x8.printf("WIFI:%-4d", macs_wifi);
u8x8.setCursor(11, 4); u8x8.setCursor(11, 4);
u8x8.printf("ch:%02d", channel); u8x8.printf("ch:%02d", channel);
// update RSSI limiter status & free memory display (line 5) // update RSSI limiter status & free memory display (line 5)
u8x8.setCursor(0, 5); u8x8.setCursor(0, 5);
u8x8.printf(!cfg.rssilimit ? "RLIM:off " : "RLIM:%-4d", cfg.rssilimit); u8x8.printf(!cfg.rssilimit ? "RLIM:off " : "RLIM:%-4d", cfg.rssilimit);
u8x8.setCursor(10, 5); u8x8.setCursor(10, 5);
u8x8.printf("%4dKB", getFreeRAM() / 1024); u8x8.printf("%4dKB", getFreeRAM() / 1024);
#ifdef HAS_LORA #ifdef HAS_LORA
// update LoRa status display (line 6) // update LoRa status display (line 6)
u8x8.setCursor(0, 6); u8x8.setCursor(0, 6);
u8x8.printf("%-16s", display_line6); u8x8.printf("%-16s", display_line6);
// update LMiC event display (line 7) // update LMiC event display (line 7)
u8x8.setCursor(0, 7); u8x8.setCursor(0, 7);
u8x8.printf("%-14s", display_line7); u8x8.printf("%-14s", display_line7);
// update LoRa send queue display (line 7) // update LoRa send queue display (line 7)
msgWaiting = uxQueueMessagesWaiting(LoraSendQueue); msgWaiting = uxQueueMessagesWaiting(LoraSendQueue);
if (msgWaiting) { if (msgWaiting) {
sprintf(buff, "%2d", msgWaiting); sprintf(buff, "%2d", msgWaiting);
u8x8.setCursor(14, 7); u8x8.setCursor(14, 7);
u8x8.printf("%-2s", msgWaiting == SEND_QUEUE_SIZE ? "<>" : buff); u8x8.printf("%-2s", msgWaiting == SEND_QUEUE_SIZE ? "<>" : buff);
} else } else
u8x8.printf(" "); u8x8.printf(" ");
#endif // HAS_LORA #endif // HAS_LORA
xSemaphoreGive(I2Caccess); // release i2c bus access
}
} // refreshDisplay() } // refreshDisplay()
#endif // HAS_DISPLAY #endif // HAS_DISPLAY

View File

@ -19,10 +19,10 @@
// user defined sensors // user defined sensors
//#define HAS_SENSORS 1 // comment out if device has user defined sensors //#define HAS_SENSORS 1 // comment out if device has user defined sensors
//#define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C #define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C
//#define MY_OLED_SDA (21) #define MY_OLED_SDA (21)
//#define MY_OLED_SCL (22) #define MY_OLED_SCL (22)
//#define MY_OLED_RST (NOT_A_PIN) #define MY_OLED_RST U8X8_PIN_NONE
//#define DISPLAY_FLIP 1 // use if display is rotated //#define DISPLAY_FLIP 1 // use if display is rotated
#define HAS_LORA 1 // comment out if device shall not send data via LoRa #define HAS_LORA 1 // comment out if device shall not send data via LoRa

View File

@ -22,7 +22,7 @@
//#define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C //#define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C
//#define MY_OLED_SDA (21) //#define MY_OLED_SDA (21)
//#define MY_OLED_SCL (22) //#define MY_OLED_SCL (22)
//#define MY_OLED_RST (NOT_A_PIN) //#define MY_OLED_RST U8X8_PIN_NONE
//#define DISPLAY_FLIP 1 // use if display is rotated //#define DISPLAY_FLIP 1 // use if display is rotated
#define HAS_LORA 1 // comment out if device shall not send data via LoRa #define HAS_LORA 1 // comment out if device shall not send data via LoRa

View File

@ -35,11 +35,14 @@ IDLE 0 0 ESP32 arduino scheduler -> runs wifi sniffer
looptask 1 1 arduino core -> runs the LMIC LoRa stack looptask 1 1 arduino core -> runs the LMIC LoRa stack
irqhandler 1 1 executes tasks triggered by irq irqhandler 1 1 executes tasks triggered by irq
gpsloop 1 2 reads data from GPS via serial or i2c gpsloop 1 2 reads data from GPS via serial or i2c
bmeloop 1 0 reads data from BME sensor via i2c bmeloop 1 1 reads data from BME sensor via i2c
IDLE 1 0 ESP32 arduino scheduler IDLE 1 0 ESP32 arduino scheduler
Low priority numbers denote low priority tasks. Low priority numbers denote low priority tasks.
Tasks using i2c bus all must have same priority, because using mutex semaphore
(irqhandler, bmeloop)
ESP32 hardware timers ESP32 hardware timers
========================== ==========================
0 Trigger display refresh 0 Trigger display refresh
@ -60,6 +63,7 @@ uint16_t volatile macs_total = 0, macs_wifi = 0, macs_ble = 0,
hw_timer_t *channelSwitch = NULL, *sendCycle = NULL, *homeCycle = NULL, hw_timer_t *channelSwitch = NULL, *sendCycle = NULL, *homeCycle = NULL,
*displaytimer = NULL; // irq tasks *displaytimer = NULL; // irq tasks
TaskHandle_t irqHandlerTask, wifiSwitchTask; TaskHandle_t irqHandlerTask, wifiSwitchTask;
SemaphoreHandle_t I2Caccess;
// container holding unique MAC address hashes with Memory Alloctor using PSRAM, // container holding unique MAC address hashes with Memory Alloctor using PSRAM,
// if present // if present
@ -78,6 +82,14 @@ void setup() {
char features[100] = ""; char features[100] = "";
if (I2Caccess == NULL) // Check that semaphore has not already been created
{
I2Caccess = xSemaphoreCreateMutex(); // Create a mutex semaphore we will use
// to manage the i2c bus
if ((I2Caccess) != NULL)
xSemaphoreGive((I2Caccess)); // Flag the i2c bus available for use
}
// disable brownout detection // disable brownout detection
#ifdef DISABLE_BROWNOUT #ifdef DISABLE_BROWNOUT
// register with brownout is at address DR_REG_RTCCNTL_BASE + 0xd4 // register with brownout is at address DR_REG_RTCCNTL_BASE + 0xd4
@ -343,11 +355,11 @@ void setup() {
"bmeloop", // name of task "bmeloop", // name of task
4096, // stack size of task 4096, // stack size of task
(void *)1, // parameter of the task (void *)1, // parameter of the task
0, // priority of the task //0, // priority of the task
1, // priority of the task
&BmeTask, // task handle &BmeTask, // task handle
1); // CPU core 1); // CPU core
} }
delay(2000); // time for initializing i2c sensor
#endif #endif
// start timer triggered interrupts // start timer triggered interrupts