diff --git a/Sensors.c b/Sensors.c
index 79af5fd..35c0eb4 100644
--- a/Sensors.c
+++ b/Sensors.c
@@ -79,7 +79,8 @@ const Interface SPI = {
static const SensorType* sensorTypes[] = {&DHT11, &DHT12_SW, &DHT20, &DHT21, &DHT22,
&Dallas, &AM2320_SW, &AM2320_I2C, &HTU21x, &AHT10,
&SHT30, &GXHT30, &LM75, &HDC1080, &BMP180,
- &BMP280, &BME280, &BME680, &MAX31855, &MAX6675};
+ &BMP280, &BME280, &BME680, &MAX31855, &MAX6675,
+ &SCD30};
const SensorType* unitemp_sensors_getTypeFromInt(uint8_t index) {
if(index > SENSOR_TYPES_COUNT) return NULL;
@@ -627,11 +628,14 @@ UnitempStatus unitemp_sensor_updateData(Sensor* sensor) {
UNITEMP_DEBUG("Sensor %s update status %d", sensor->name, sensor->status);
}
- if(app->settings.temp_unit == UT_TEMP_FAHRENHEIT && sensor->status == UT_SENSORSTATUS_OK) {
- uintemp_celsiumToFarengate(sensor);
- }
-
if(sensor->status == UT_SENSORSTATUS_OK) {
+ if(app->settings.heat_index && ((sensor->type->datatype & (UT_TEMPERATURE | UT_HUMIDITY)) == (UT_TEMPERATURE | UT_HUMIDITY))) {
+ unitemp_calculate_heat_index(sensor);
+ }
+ if(app->settings.temp_unit == UT_TEMP_FAHRENHEIT) {
+ uintemp_celsiumToFarengate(sensor);
+ }
+
sensor->temp += sensor->temp_offset / 10.f;
if(app->settings.pressure_unit == UT_PRESSURE_MM_HG) {
unitemp_pascalToMmHg(sensor);
diff --git a/Sensors.h b/Sensors.h
index d2b7c07..467f574 100644
--- a/Sensors.h
+++ b/Sensors.h
@@ -24,6 +24,7 @@
#define UT_TEMPERATURE 0b00000001
#define UT_HUMIDITY 0b00000010
#define UT_PRESSURE 0b00000100
+#define UT_CO2 0b00001000
//Статусы опроса датчика
typedef enum {
@@ -31,6 +32,7 @@ typedef enum {
UT_DATA_TYPE_TEMP_HUM = UT_TEMPERATURE | UT_HUMIDITY,
UT_DATA_TYPE_TEMP_PRESS = UT_TEMPERATURE | UT_PRESSURE,
UT_DATA_TYPE_TEMP_HUM_PRESS = UT_TEMPERATURE | UT_HUMIDITY | UT_PRESSURE,
+ UT_DATA_TYPE_TEMP_HUM_CO2 = UT_TEMPERATURE | UT_HUMIDITY | UT_CO2,
} SensorDataType;
//Типы возвращаемых данных
@@ -117,10 +119,13 @@ typedef struct Sensor {
char* name;
//Температура
float temp;
+ float heat_index;
//Относительная влажность
float hum;
//Атмосферное давление
float pressure;
+ // Концентрация CO2
+ float co2;
//Тип датчика
const SensorType* type;
//Статус последнего опроса датчика
@@ -329,4 +334,5 @@ const GPIO*
#include "./sensors/HDC1080.h"
#include "./sensors/MAX31855.h"
#include "./sensors/MAX6675.h"
+#include "./sensors/SCD30.h"
#endif
diff --git a/assets/co2_11x14.png b/assets/co2_11x14.png
new file mode 100644
index 0000000..2a2b5e0
Binary files /dev/null and b/assets/co2_11x14.png differ
diff --git a/assets/heat_index_11x14.png b/assets/heat_index_11x14.png
new file mode 100644
index 0000000..f2f0d4c
Binary files /dev/null and b/assets/heat_index_11x14.png differ
diff --git a/sensors/SCD30.c b/sensors/SCD30.c
new file mode 100644
index 0000000..dd045df
--- /dev/null
+++ b/sensors/SCD30.c
@@ -0,0 +1,448 @@
+/*
+ Unitemp - Universal temperature reader
+ Copyright (C) 2022-2023 Victor Nikitchuk (https://github.com/quen0n)
+ Contributed by divinebird (https://github.com/divinebird)
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see .
+*/
+
+// Some information may be seen on https://github.com/sparkfun/SparkFun_SCD30_Arduino_Library
+
+#include "SCD30.h"
+#include "../interfaces/I2CSensor.h"
+//#include <3rdparty/everest/include/everest/kremlin/c_endianness.h>
+
+inline static uint16_t load16(uint8_t *b) {
+ uint16_t x;
+ memcpy(&x, b, 2);
+ return x;
+}
+
+inline static uint32_t load32(uint8_t *b) {
+ uint32_t x;
+ memcpy(&x, b, 4);
+ return x;
+}
+
+inline static void store16(uint8_t *b, uint16_t i) {
+ memcpy(b, &i, 2);
+}
+
+inline static void store32(uint8_t *b, uint32_t i) {
+ memcpy(b, &i, 4);
+}
+
+#if BYTE_ORDER == BIG_ENDIAN
+ #define htobe16(x) (x)
+ #define htobe32(x) (x)
+ #define htole16(x) __builtin_bswap16 (x)
+ #define htole32(x) __builtin_bswap32 (x)
+ #define be16toh(x) (x)
+ #define be32toh(x) (x)
+ #define le16toh(x) __builtin_bswap16 (x)
+ #define le32toh(x) __builtin_bswap32 (x)
+#elif BYTE_ORDER == LITTLE_ENDIAN
+ #define htobe16(x) __builtin_bswap16 (x)
+ #define htobe32(x) __builtin_bswap32 (x)
+ #define htole16(x) (x)
+ #define htole32(x) (x)
+ #define be16toh(x) __builtin_bswap16 (x)
+ #define be32toh(x) __builtin_bswap32 (x)
+ #define le16toh(x) (x)
+ #define le32toh(x) (x)
+#else
+ # error "What kind of system is this?"
+#endif
+
+#define load16_le(b) (le16toh(load16(b)))
+#define load32_le(b) (le32toh(load32(b)))
+#define store16_le(b, i) (store16(b, htole16(i)))
+#define store32_le(b, i) (store32(b, htole32(i)))
+
+#define load16_be(b) (be16toh(load16(b)))
+#define load32_be(b) (be32toh(load32(b)))
+#define store16_be(b, i) (store16(b, htobe16(i)))
+#define store32_be(b, i) (store32(b, htobe32(i)))
+
+typedef union {
+ uint16_t array16[2];
+ uint8_t array8[4];
+ float value;
+} ByteToFl;
+
+
+bool unitemp_SCD30_alloc(Sensor* sensor, char* args);
+bool unitemp_SCD30_init(Sensor* sensor);
+bool unitemp_SCD30_deinit(Sensor* sensor);
+UnitempStatus unitemp_SCD30_update(Sensor* sensor);
+bool unitemp_SCD30_free(Sensor* sensor);
+
+const SensorType SCD30 = {
+ .typename = "SCD30",
+ .interface = &I2C,
+ .datatype = UT_DATA_TYPE_TEMP_HUM_CO2,
+ .pollingInterval = 2000,
+ .allocator = unitemp_SCD30_alloc,
+ .mem_releaser = unitemp_SCD30_free,
+ .initializer = unitemp_SCD30_init,
+ .deinitializer = unitemp_SCD30_deinit,
+ .updater = unitemp_SCD30_update};
+
+#define SCD30_ID 0x61
+
+#define COMMAND_CONTINUOUS_MEASUREMENT 0x0010
+#define COMMAND_SET_MEASUREMENT_INTERVAL 0x4600
+#define COMMAND_GET_DATA_READY 0x0202
+#define COMMAND_READ_MEASUREMENT 0x0300
+#define COMMAND_AUTOMATIC_SELF_CALIBRATION 0x5306
+#define COMMAND_SET_FORCED_RECALIBRATION_FACTOR 0x5204
+#define COMMAND_SET_TEMPERATURE_OFFSET 0x5403
+#define COMMAND_SET_ALTITUDE_COMPENSATION 0x5102
+#define COMMAND_RESET 0xD304 // Soft reset
+#define COMMAND_STOP_MEAS 0x0104
+#define COMMAND_READ_FW_VER 0xD100
+
+static bool dataAvailable(Sensor* sensor) __attribute__((unused));
+static bool readMeasurement(Sensor* sensor) __attribute__((unused));
+static void reset(Sensor* sensor) __attribute__((unused));
+
+static bool setAutoSelfCalibration(Sensor* sensor, bool enable) __attribute__((unused));
+static bool getAutoSelfCalibration(Sensor* sensor) __attribute__((unused));
+
+static bool getFirmwareVersion(Sensor* sensor, uint16_t* val) __attribute__((unused));
+
+static bool setForcedRecalibrationFactor(Sensor* sensor, uint16_t concentration) __attribute__((unused));
+static uint16_t getAltitudeCompensation(Sensor* sensor) __attribute__((unused));
+static bool setAltitudeCompensation(Sensor* sensor, uint16_t altitude) __attribute__((unused));
+static bool setAmbientPressure(Sensor* sensor, uint16_t pressure_mbar) __attribute__((unused));
+
+static float getTemperatureOffset(Sensor* sensor) __attribute__((unused));
+static bool setTemperatureOffset(Sensor* sensor, float tempOffset) __attribute__((unused));
+
+static bool beginMeasuringWithSettings(Sensor* sensor, uint16_t pressureOffset) __attribute__((unused));
+static bool beginMeasuring(Sensor* sensor) __attribute__((unused));
+static bool stopMeasurement(Sensor* sensor) __attribute__((unused));
+
+static bool setMeasurementInterval(Sensor* sensor, uint16_t interval) __attribute__((unused));
+static uint16_t getMeasurementInterval(Sensor* sensor) __attribute__((unused));
+
+bool unitemp_SCD30_alloc(Sensor* sensor, char* args) {
+ UNUSED(args);
+ I2CSensor* i2c_sensor = (I2CSensor*)sensor->instance;
+
+ i2c_sensor->minI2CAdr = SCD30_ID << 1;
+ i2c_sensor->maxI2CAdr = SCD30_ID << 1;
+ return true;
+}
+
+bool unitemp_SCD30_free(Sensor* sensor) {
+ //Нечего высвобождать, так как ничего не было выделено
+ UNUSED(sensor);
+ return true;
+}
+
+bool unitemp_SCD30_init(Sensor* sensor) {
+ if(beginMeasuring(sensor) == true) { // Start continuous measurements
+ setMeasurementInterval(sensor, SCD30.pollingInterval/1000);
+ setAutoSelfCalibration(sensor, true);
+ setAmbientPressure(sensor, 0);
+ }
+ else
+ return false;
+
+ return true;
+}
+
+bool unitemp_SCD30_deinit(Sensor* sensor) {
+ return stopMeasurement(sensor);
+}
+
+UnitempStatus unitemp_SCD30_update(Sensor* sensor) {
+ readMeasurement(sensor);
+ return UT_SENSORSTATUS_OK;
+}
+
+static uint8_t computeCRC8(uint8_t* message, uint8_t len) {
+ uint8_t crc = 0xFF; // Init with 0xFF
+ for (uint8_t x = 0; x < len; x++) {
+ crc ^= message[x]; // XOR-in the next input byte
+ for (uint8_t i = 0; i < 8; i++) {
+ if ((crc & 0x80) != 0)
+ crc = (uint8_t)((crc << 1) ^ 0x31);
+ else
+ crc <<= 1;
+ }
+ }
+ return crc; // No output reflection
+}
+
+// Sends a command along with arguments and CRC
+static bool sendCommandWithCRC(Sensor* sensor, uint16_t command, uint16_t arguments) {
+ static const uint8_t cmdSize = 5;
+
+ uint8_t bytes[cmdSize];
+ uint8_t *pointer = bytes;
+ store16_be(pointer, command);
+ pointer += 2;
+ uint8_t *argPos = pointer;
+ store16_be(pointer, arguments);
+ pointer += 2;
+ *pointer = computeCRC8(argPos, pointer - argPos);
+
+ I2CSensor* i2c_sensor = (I2CSensor*)sensor->instance;
+ return unitemp_i2c_writeArray(i2c_sensor, cmdSize, bytes);
+}
+
+// Sends just a command, no arguments, no CRC
+static bool sendCommand(Sensor* sensor, uint16_t command) {
+ static const uint8_t cmdSize = 2;
+
+ uint8_t bytes[cmdSize];
+ store16_be(bytes, command);
+
+ I2CSensor* i2c_sensor = (I2CSensor*)sensor->instance;
+ return unitemp_i2c_writeArray(i2c_sensor, cmdSize, bytes);
+}
+
+static uint16_t readRegister(Sensor* sensor, uint16_t registerAddress) {
+ static const uint8_t regSize = 2;
+
+ if(!sendCommand(sensor, registerAddress))
+ return 0; // Sensor did not ACK
+
+ furi_delay_ms(3);
+
+ uint8_t bytes[regSize];
+ I2CSensor* i2c_sensor = (I2CSensor*)sensor->instance;
+ if(!unitemp_i2c_readArray(i2c_sensor, regSize, bytes))
+ return 0;
+
+ return load16_be(bytes);
+}
+
+static bool loadWord(uint8_t* buff, uint16_t* val) {
+ uint16_t tmp = load16_be(buff);
+ uint8_t expectedCRC = computeCRC8(buff, 2);
+ if(buff[2] != expectedCRC)
+ return false;
+ *val = tmp;
+ return true;
+}
+
+static bool getSettingValue(Sensor* sensor, uint16_t registerAddress, uint16_t* val) {
+ static const uint8_t respSize = 3;
+
+ if(!sendCommand(sensor, registerAddress))
+ return false; // Sensor did not ACK
+
+ furi_delay_ms(3);
+
+ uint8_t bytes[respSize];
+ I2CSensor* i2c_sensor = (I2CSensor*)sensor->instance;
+ if(!unitemp_i2c_readArray(i2c_sensor, respSize, bytes))
+ return false;
+
+ return loadWord(bytes, val);
+}
+
+static bool loadFloat(uint8_t* buff, float* val) {
+// ByteToFl tmp;
+ size_t cntr = 0;
+ uint8_t floatBuff[4];
+ for(size_t i = 0; i < 2; i++) {
+ floatBuff[cntr++] = buff[0];
+ floatBuff[cntr++] = buff[1];
+ uint8_t expectedCRC = computeCRC8(buff, 2);
+ if(buff[2] != expectedCRC) return false;
+ buff += 3;
+ }
+ uint32_t tmpVal = load32_be(floatBuff);
+ *val = *(float*)&tmpVal;
+ return true;
+}
+
+// Get 18 bytes from SCD30
+// Updates global variables with floats
+// Returns true if success
+static bool readMeasurement(Sensor* sensor) {
+ // Verify we have data from the sensor
+ if(!dataAvailable(sensor)) {
+ return false;
+ }
+
+ if(!sendCommand(sensor, COMMAND_READ_MEASUREMENT)) {
+ FURI_LOG_E(APP_NAME, "Sensor did not ACK");
+ return false; // Sensor did not ACK
+ }
+
+ float tempCO2 = 0;
+ float tempHumidity = 0;
+ float tempTemperature = 0;
+
+ furi_delay_ms(3);
+
+ static const uint8_t respSize = 18;
+ uint8_t buff[respSize];
+ uint8_t* bytes = buff;
+ I2CSensor* i2c_sensor = (I2CSensor*)sensor->instance;
+ if(!unitemp_i2c_readArray(i2c_sensor, respSize, bytes)) {
+ FURI_LOG_E(APP_NAME, "Error while read measures");
+ return false;
+ }
+
+ bool error = false;
+ if(loadFloat(bytes, &tempCO2)) {
+ sensor->co2 = tempCO2;
+ }
+ else {
+ FURI_LOG_E(APP_NAME, "Error while parsing CO2");
+ error = true;
+ }
+
+ bytes += 6;
+ if(loadFloat(bytes, &tempTemperature)) {
+ sensor->temp = tempTemperature;
+ }
+ else {
+ FURI_LOG_E(APP_NAME, "Error while parsing temp");
+ error = true;
+ }
+
+ bytes += 6;
+ if(loadFloat(bytes, &tempHumidity)) {
+ sensor->hum = tempHumidity;
+ }
+ else {
+ FURI_LOG_E(APP_NAME, "Error while parsing humidity");
+ error = true;
+ }
+
+ return !error;
+}
+
+static void reset(Sensor* sensor) {
+ sendCommand(sensor, COMMAND_RESET);
+}
+
+static bool setAutoSelfCalibration(Sensor* sensor, bool enable) {
+ return sendCommandWithCRC(sensor, COMMAND_AUTOMATIC_SELF_CALIBRATION, enable); // Activate continuous ASC
+}
+
+// Get the current ASC setting
+static bool getAutoSelfCalibration(Sensor* sensor) {
+ return 1 == readRegister(sensor, COMMAND_AUTOMATIC_SELF_CALIBRATION);
+}
+
+static bool getFirmwareVersion(Sensor* sensor, uint16_t* val) {
+ return getSettingValue(sensor, COMMAND_READ_FW_VER, val);
+}
+
+// Set the forced recalibration factor. See 1.3.7.
+// The reference CO2 concentration has to be within the range 400 ppm ≤ cref(CO2) ≤ 2000 ppm.
+static bool setForcedRecalibrationFactor(Sensor* sensor, uint16_t concentration) {
+ if (concentration < 400 || concentration > 2000) {
+ return false; // Error check.
+ }
+ return sendCommandWithCRC(sensor, COMMAND_SET_FORCED_RECALIBRATION_FACTOR, concentration);
+}
+
+// Get the temperature offset. See 1.3.8.
+static float getTemperatureOffset(Sensor* sensor) {
+ union {
+ int16_t signed16;
+ uint16_t unsigned16;
+ } signedUnsigned; // Avoid any ambiguity casting int16_t to uint16_t
+ signedUnsigned.unsigned16 = readRegister(sensor, COMMAND_SET_TEMPERATURE_OFFSET);
+
+ return ((float)signedUnsigned.signed16) / 100.0;
+}
+
+static bool setTemperatureOffset(Sensor* sensor, float tempOffset) {
+ // Temp offset is only positive. See: https://github.com/sparkfun/SparkFun_SCD30_Arduino_Library/issues/27#issuecomment-971986826
+ //"The SCD30 offset temperature is obtained by subtracting the reference temperature from the SCD30 output temperature"
+ // https://www.sensirion.com/fileadmin/user_upload/customers/sensirion/Dokumente/9.5_CO2/Sensirion_CO2_Sensors_SCD30_Low_Power_Mode.pdf
+
+ if (tempOffset < 0.0)
+ return false;
+
+ uint16_t value = tempOffset * 100;
+
+ return sendCommandWithCRC(sensor, COMMAND_SET_TEMPERATURE_OFFSET, value);
+}
+
+// Get the altitude compenstation. See 1.3.9.
+static uint16_t getAltitudeCompensation(Sensor* sensor) {
+ return readRegister(sensor, COMMAND_SET_ALTITUDE_COMPENSATION);
+}
+
+// Set the altitude compenstation. See 1.3.9.
+static bool setAltitudeCompensation(Sensor* sensor, uint16_t altitude) {
+ return sendCommandWithCRC(sensor, COMMAND_SET_ALTITUDE_COMPENSATION, altitude);
+}
+
+// Set the pressure compenstation. This is passed during measurement startup.
+// mbar can be 700 to 1200
+static bool setAmbientPressure(Sensor* sensor, uint16_t pressure_mbar) {
+ if (pressure_mbar != 0 || pressure_mbar < 700 || pressure_mbar > 1200) {
+ return false;
+ }
+ return sendCommandWithCRC(sensor, COMMAND_CONTINUOUS_MEASUREMENT, pressure_mbar);
+}
+
+// Begins continuous measurements
+// Continuous measurement status is saved in non-volatile memory. When the sensor
+// is powered down while continuous measurement mode is active SCD30 will measure
+// continuously after repowering without sending the measurement command.
+// Returns true if successful
+static bool beginMeasuringWithSettings(Sensor* sensor, uint16_t pressureOffset) {
+ return sendCommandWithCRC(sensor, COMMAND_CONTINUOUS_MEASUREMENT, pressureOffset);
+}
+
+// Overload - no pressureOffset
+static bool beginMeasuring(Sensor* sensor) {
+ return beginMeasuringWithSettings(sensor, 0);
+}
+
+// Stop continuous measurement
+static bool stopMeasurement(Sensor* sensor) {
+ return sendCommand(sensor, COMMAND_STOP_MEAS);
+}
+
+// Sets interval between measurements
+// 2 seconds to 1800 seconds (30 minutes)
+static bool setMeasurementInterval(Sensor* sensor, uint16_t interval) {
+ if(interval < 2 || interval > 1800)
+ return false;
+ if(!sendCommandWithCRC(sensor, COMMAND_SET_MEASUREMENT_INTERVAL, interval))
+ return false;
+ uint16_t verInterval = readRegister(sensor, COMMAND_SET_MEASUREMENT_INTERVAL);
+ if(verInterval != interval) {
+ FURI_LOG_E(APP_NAME, "Measure interval wrong! Val: %02x", verInterval);
+ return false;
+ }
+ return true;
+}
+
+// Gets interval between measurements
+// 2 seconds to 1800 seconds (30 minutes)
+static uint16_t getMeasurementInterval(Sensor* sensor) {
+ uint16_t interval = 0;
+ getSettingValue(sensor, COMMAND_SET_MEASUREMENT_INTERVAL, &interval);
+ return interval;
+}
+
+// Returns true when data is available
+static bool dataAvailable(Sensor* sensor) {
+ return 1 == readRegister(sensor, COMMAND_GET_DATA_READY);
+}
\ No newline at end of file
diff --git a/sensors/SCD30.h b/sensors/SCD30.h
new file mode 100644
index 0000000..1ebfbb4
--- /dev/null
+++ b/sensors/SCD30.h
@@ -0,0 +1,59 @@
+/*
+ Unitemp - Universal temperature reader
+ Copyright (C) 2022-2023 Victor Nikitchuk (https://github.com/quen0n)
+ Contributed by divinebird (https://github.com/divinebird)
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see .
+*/
+#ifndef UNITEMP_SCD30
+#define UNITEMP_SCD30
+
+#include "../unitemp.h"
+#include "../Sensors.h"
+
+extern const SensorType SCD30;
+/**
+ * @brief Выделение памяти и установка начальных значений датчика SCD30
+ * @param sensor Указатель на создаваемый датчик
+ * @return Истина при успехе
+ */
+bool unitemp_SCD30_alloc(Sensor* sensor, char* args);
+
+/**
+ * @brief Инициализации датчика SCD30
+ * @param sensor Указатель на датчик
+ * @return Истина если инициализация упспешная
+ */
+bool unitemp_SCD30_init(Sensor* sensor);
+
+/**
+ * @brief Деинициализация датчика
+ * @param sensor Указатель на датчик
+ */
+bool unitemp_SCD30_deinit(Sensor* sensor);
+
+/**
+ * @brief Обновление значений из датчика
+ * @param sensor Указатель на датчик
+ * @return Статус опроса датчика
+ */
+UnitempStatus unitemp_SCD30_update(Sensor* sensor);
+
+/**
+ * @brief Высвободить память датчика
+ * @param sensor Указатель на датчик
+ */
+bool unitemp_SCD30_free(Sensor* sensor);
+
+#endif
\ No newline at end of file
diff --git a/unitemp.c b/unitemp.c
index 181de0e..8263068 100644
--- a/unitemp.c
+++ b/unitemp.c
@@ -28,8 +28,24 @@ Unitemp* app;
void uintemp_celsiumToFarengate(Sensor* sensor) {
sensor->temp = sensor->temp * (9.0 / 5.0) + 32;
+ sensor->heat_index = sensor->heat_index * (9.0 / 5.0) + 32;
}
+static float heat_index_consts[9] = {-42.379f, 2.04901523f, 10.14333127f, -0.22475541f, -0.00683783f, -0.05481717f, 0.00122874f, 0.00085282f, -0.00000199f};
+void unitemp_calculate_heat_index(Sensor* sensor) {
+ // temp should be in Celsius, heat index will be in Celsius
+ float temp = sensor->temp * (9.0 / 5.0) + 32.0f;
+ float hum = sensor->hum;
+ sensor->heat_index = (heat_index_consts[0]
+ + heat_index_consts[1] * temp
+ + heat_index_consts[2] * hum
+ + heat_index_consts[3] * temp * hum
+ + heat_index_consts[4] * temp * temp
+ + heat_index_consts[5] * hum * hum
+ + heat_index_consts[6] * temp * temp * hum
+ + heat_index_consts[7] * temp * hum * hum
+ + heat_index_consts[8] * temp * temp * hum * hum - 32.0f) * (5.0 / 9.0);
+}
void unitemp_pascalToMmHg(Sensor* sensor) {
sensor->pressure = sensor->pressure * 0.007500638;
}
@@ -68,6 +84,7 @@ bool unitemp_saveSettings(void) {
app->file_stream, "INFINITY_BACKLIGHT %d\n", app->settings.infinityBacklight);
stream_write_format(app->file_stream, "TEMP_UNIT %d\n", app->settings.temp_unit);
stream_write_format(app->file_stream, "PRESSURE_UNIT %d\n", app->settings.pressure_unit);
+ stream_write_format(app->file_stream, "HEAT_INDEX %d\n", app->settings.heat_index);
//Закрытие потока и освобождение памяти
file_stream_close(app->file_stream);
@@ -163,6 +180,11 @@ bool unitemp_loadSettings(void) {
int p = 0;
sscanf(((char*)(file_buf + line_end)), "\nPRESSURE_UNIT %d", &p);
app->settings.pressure_unit = p;
+ } else if(!strcmp(buff, "HEAT_INDEX")) {
+ //Чтение значения параметра
+ int p = 0;
+ sscanf(((char*)(file_buf + line_end)), "\nHEAT_INDEX %d", &p);
+ app->settings.heat_index = p;
} else {
FURI_LOG_W(APP_NAME, "Unknown settings parameter: %s", buff);
}
@@ -200,6 +222,7 @@ static bool unitemp_alloc(void) {
app->settings.infinityBacklight = true; //Подсветка горит всегда
app->settings.temp_unit = UT_TEMP_CELSIUS; //Единица измерения температуры - градусы Цельсия
app->settings.pressure_unit = UT_PRESSURE_MM_HG; //Единица измерения давления - мм рт. ст.
+ app->settings.heat_index = false;
app->gui = furi_record_open(RECORD_GUI);
//Диспетчер окон
diff --git a/unitemp.h b/unitemp.h
index bde8b0c..3ed7ff6 100644
--- a/unitemp.h
+++ b/unitemp.h
@@ -79,6 +79,8 @@ typedef struct {
tempMeasureUnit temp_unit;
//Единица измерения давления
pressureMeasureUnit pressure_unit;
+ // Do calculate and show heat index
+ bool heat_index;
//Последнее состояние OTG
bool lastOTGState;
} UnitempSettings;
@@ -110,6 +112,13 @@ typedef struct {
/* Объявление прототипов функций */
+/**
+ * @brief Calculates the heat index in Celsius from the temperature and humidity and stores it in the sensor heat_index field
+ *
+ * @param sensor The sensor struct, with temperature in Celcius and humidity in percent
+ */
+void unitemp_calculate_heat_index(Sensor* sensor);
+
/**
* @brief Перевод значения температуры датчика из Цельсия в Фаренгейты
*
diff --git a/views/General_view.c b/views/General_view.c
index dcf8420..1903e52 100644
--- a/views/General_view.c
+++ b/views/General_view.c
@@ -113,6 +113,33 @@ static void _draw_humidity(Canvas* canvas, Sensor* sensor, const uint8_t pos[2])
canvas_draw_str(canvas, pos[0] + 27 + int_len / 2 + 4, pos[1] + 10 + 7, "%");
}
+static void _draw_heat_index(Canvas* canvas, Sensor* sensor, const uint8_t pos[2]) {
+ canvas_draw_rframe(canvas, pos[0], pos[1], 54, 20, 3);
+ canvas_draw_rframe(canvas, pos[0], pos[1], 54, 19, 3);
+
+ canvas_draw_icon(canvas, pos[0] + 3, pos[1] + 3, &I_heat_index_11x14);
+
+ int16_t heat_index_int = sensor->heat_index;
+ int8_t heat_index_dec = abs((int16_t)(sensor->heat_index * 10) % 10);
+
+ snprintf(app->buff, BUFF_SIZE, "%d", heat_index_int);
+ canvas_set_font(canvas, FontBigNumbers);
+ canvas_draw_str_aligned(
+ canvas,
+ pos[0] + 27 + ((sensor->heat_index <= -10 || sensor->heat_index > 99) ? 5 : 0),
+ pos[1] + 10,
+ AlignCenter,
+ AlignCenter,
+ app->buff);
+
+ if(heat_index_int <= 99) {
+ uint8_t int_len = canvas_string_width(canvas, app->buff);
+ snprintf(app->buff, BUFF_SIZE, ".%d", heat_index_dec);
+ canvas_set_font(canvas, FontPrimary);
+ canvas_draw_str(canvas, pos[0] + 27 + int_len / 2 + 2, pos[1] + 10 + 7, app->buff);
+ }
+}
+
static void _draw_pressure(Canvas* canvas, Sensor* sensor) {
const uint8_t x = 29, y = 39;
//Рисование рамки
@@ -148,6 +175,35 @@ static void _draw_pressure(Canvas* canvas, Sensor* sensor) {
}
}
+static void _draw_co2(Canvas* canvas, Sensor* sensor, Color color) {
+ const uint8_t x = 29, y = 39;
+ //Рисование рамки
+ canvas_draw_rframe(canvas, x, y, 75, 20, 3);
+ if(color == ColorBlack) {
+ canvas_draw_rbox(canvas, x, y, 75, 19, 3);
+ canvas_invert_color(canvas);
+ } else {
+ canvas_draw_rframe(canvas, x, y, 75, 19, 3);
+ }
+
+ //Рисование иконки
+ canvas_draw_icon(canvas, x + 3, y + 3, &I_co2_11x14);
+
+ int16_t concentration_int = sensor->co2;
+ // int8_t concentration_dec = (int16_t)(sensor->co2 * 10) % 10;
+
+ //Целая часть
+ if(concentration_int > 9999) {
+ snprintf(app->buff, BUFF_SIZE, "MAX ");
+ canvas_set_font(canvas, FontPrimary);
+ } else {
+ snprintf(app->buff, BUFF_SIZE, "%d", concentration_int);
+ canvas_set_font(canvas, FontBigNumbers);
+ }
+
+ canvas_draw_str_aligned(canvas, x + 70, y + 10, AlignRight, AlignCenter, app->buff);
+}
+
static void _draw_singleSensor(Canvas* canvas, Sensor* sensor, const uint8_t pos[2], Color color) {
canvas_set_font(canvas, FontPrimary);
@@ -277,12 +333,23 @@ static void _draw_carousel_values(Canvas* canvas) {
ColorWhite);
break;
case UT_DATA_TYPE_TEMP_HUM:
- _draw_temperature(
- canvas,
- unitemp_sensor_getActive(generalview_sensor_index),
- temp_positions[1][0],
- temp_positions[1][1],
- ColorWhite);
+ if(!app->settings.heat_index) {
+ _draw_temperature(
+ canvas,
+ unitemp_sensor_getActive(generalview_sensor_index),
+ temp_positions[1][0],
+ temp_positions[1][1],
+ ColorWhite);
+ } else {
+ _draw_temperature(
+ canvas,
+ unitemp_sensor_getActive(generalview_sensor_index),
+ temp_positions[2][0],
+ temp_positions[2][1],
+ ColorWhite);
+ _draw_heat_index(
+ canvas, unitemp_sensor_getActive(generalview_sensor_index), hum_positions[1]);
+ }
_draw_humidity(
canvas, unitemp_sensor_getActive(generalview_sensor_index), hum_positions[0]);
break;
@@ -306,6 +373,17 @@ static void _draw_carousel_values(Canvas* canvas) {
canvas, unitemp_sensor_getActive(generalview_sensor_index), hum_positions[1]);
_draw_pressure(canvas, unitemp_sensor_getActive(generalview_sensor_index));
break;
+ case UT_DATA_TYPE_TEMP_HUM_CO2:
+ _draw_temperature(
+ canvas,
+ unitemp_sensor_getActive(generalview_sensor_index),
+ temp_positions[2][0],
+ temp_positions[2][1],
+ ColorWhite);
+ _draw_humidity(
+ canvas, unitemp_sensor_getActive(generalview_sensor_index), hum_positions[1]);
+ _draw_co2(canvas, unitemp_sensor_getActive(generalview_sensor_index), ColorWhite);
+ break;
}
}
diff --git a/views/Settings_view.c b/views/Settings_view.c
index bff1691..1f5f2a3 100644
--- a/views/Settings_view.c
+++ b/views/Settings_view.c
@@ -26,6 +26,7 @@ static VariableItemList* variable_item_list;
static const char states[2][9] = {"Auto", "Infinity"};
static const char temp_units[UT_TEMP_COUNT][3] = {"*C", "*F"};
static const char pressure_units[UT_PRESSURE_COUNT][6] = {"mm Hg", "in Hg", "kPa"};
+static const char heat_index_bool[2][4] = {"OFF", "ON"};
//Элемент списка - бесконечная подсветка
VariableItem* infinity_backlight_item;
@@ -33,6 +34,8 @@ VariableItem* infinity_backlight_item;
VariableItem* temperature_unit_item;
//Единица измерения давления
VariableItem* pressure_unit_item;
+
+VariableItem* heat_index_item;
#define VIEW_ID UnitempViewSettings
/**
@@ -57,6 +60,7 @@ static uint32_t _exit_callback(void* context) {
(bool)variable_item_get_current_value_index(infinity_backlight_item);
app->settings.temp_unit = variable_item_get_current_value_index(temperature_unit_item);
app->settings.pressure_unit = variable_item_get_current_value_index(pressure_unit_item);
+ app->settings.heat_index = variable_item_get_current_value_index(heat_index_item);
unitemp_saveSettings();
unitemp_loadSettings();
@@ -90,6 +94,11 @@ static void _setting_change_callback(VariableItem* item) {
pressure_unit_item,
pressure_units[variable_item_get_current_value_index(pressure_unit_item)]);
}
+ if(item == heat_index_item) {
+ variable_item_set_current_value_text(
+ heat_index_item,
+ heat_index_bool[variable_item_get_current_value_index(heat_index_item)]);
+ }
}
/**
@@ -106,6 +115,8 @@ void unitemp_Settings_alloc(void) {
variable_item_list_add(variable_item_list, "Temp. unit", 2, _setting_change_callback, app);
pressure_unit_item = variable_item_list_add(
variable_item_list, "Press. unit", UT_PRESSURE_COUNT, _setting_change_callback, app);
+ heat_index_item = variable_item_list_add(
+ variable_item_list, "Calc. heat index", 2, _setting_change_callback, app);
//Добавление колбека на нажатие средней кнопки
variable_item_list_set_enter_callback(variable_item_list, _enter_callback, app);
@@ -139,6 +150,11 @@ void unitemp_Settings_switch(void) {
pressure_unit_item,
pressure_units[variable_item_get_current_value_index(pressure_unit_item)]);
+ variable_item_set_current_value_index(
+ heat_index_item, (uint8_t)app->settings.heat_index);
+ variable_item_set_current_value_text(
+ heat_index_item, heat_index_bool[variable_item_get_current_value_index(heat_index_item)]);
+
view_dispatcher_switch_to_view(app->view_dispatcher, VIEW_ID);
}