From: Manfred Steiner Date: Thu, 1 Aug 2024 13:19:21 +0000 (+0200) Subject: ... X-Git-Url: https://git.htl-mechatronik.at/public/?a=commitdiff_plain;h=b083899ad03f228fc36071b6c89227adbcbc8b1b;p=nano-x-base.git ... --- diff --git a/software/test_2024-07-23/src/adafruit/arduino.cpp b/software/test_2024-07-23/src/adafruit/arduino.cpp new file mode 100644 index 0000000..055b842 --- /dev/null +++ b/software/test_2024-07-23/src/adafruit/arduino.cpp @@ -0,0 +1,28 @@ +#include "arduino.h" + +Adafruit_I2CDevice::Adafruit_I2CDevice (uint8_t addr) { +} + + +bool Adafruit_I2CDevice::begin (bool addr_detect) { + return false; +} + +void Adafruit_I2CDevice::end (void) { + +} + +bool Adafruit_I2CDevice::read (uint8_t *buffer, size_t len, bool stop) { + return false; +} + +bool Adafruit_I2CDevice::write (const uint8_t *buffer, size_t len) { + return false; +} + +// bool write(const uint8_t *buffer, size_t len, bool stop = true, +// const uint8_t *prefix_buffer = nullptr, size_t prefix_len = 0); + +bool Adafruit_I2CDevice::write_then_read (const uint8_t *write_buffer, size_t write_len, uint8_t *read_buffer, size_t read_len, bool stop) { + return false; +} diff --git a/software/test_2024-07-23/src/adafruit/arduino.h b/software/test_2024-07-23/src/adafruit/arduino.h new file mode 100644 index 0000000..8ec8334 --- /dev/null +++ b/software/test_2024-07-23/src/adafruit/arduino.h @@ -0,0 +1,46 @@ +#ifndef __ARDUINO_H__ +#define __ARDUINO_H__ + +#include +#include + +#define byte uint8_t + + + +class Adafruit_SPIDevice {}; + +class SPIClass {}; + +class TwoWire {}; + +extern SPIClass SPI; +extern TwoWire Wire; +extern uint32_t millis (); + +class Adafruit_I2CDevice { + public: + Adafruit_I2CDevice(uint8_t addr); + bool begin(bool addr_detect = true); + void end(void); + bool read(uint8_t *buffer, size_t len, bool stop = true); + bool write(const uint8_t *buffer, size_t len); + // bool write(const uint8_t *buffer, size_t len, bool stop = true, + // const uint8_t *prefix_buffer = nullptr, size_t prefix_len = 0); + + bool write_then_read(const uint8_t *write_buffer, size_t write_len, + uint8_t *read_buffer, size_t read_len, + bool stop = false); + + + private: + uint8_t _addr; + TwoWire *_wire; + bool _begun; + size_t _maxBufferSize; + bool _read(uint8_t *buffer, size_t len, bool stop); +}; + + + +#endif \ No newline at end of file diff --git a/software/test_2024-07-23/src/adafruit/bme280.cpp b/software/test_2024-07-23/src/adafruit/bme280.cpp new file mode 100644 index 0000000..049e9a6 --- /dev/null +++ b/software/test_2024-07-23/src/adafruit/bme280.cpp @@ -0,0 +1,575 @@ +/*! + * @file Adafruit_BME280.cpp + * + * @mainpage Adafruit BME280 humidity, temperature & pressure sensor + * + * @section intro_sec Introduction + * + * Driver for the BME280 humidity, temperature & pressure sensor + * + * These sensors use I2C or SPI to communicate, 2 or 4 pins are required + * to interface. + * + * Designed specifically to work with the Adafruit BME280 Breakout + * ----> http://www.adafruit.com/products/2652 + * + * Adafruit invests time and resources providing this open source code, + * please support Adafruit and open-source hardware by purchasing + * products from Adafruit! + * + * @section author Author + * + * Written by Kevin "KTOWN" Townsend for Adafruit Industries. + * + * @section license License + * + * BSD license, all text here must be included in any redistribution. + * See the LICENSE file for details. + * + */ + +// #include "Adafruit_BME280.h" +// #include "Arduino.h" + +#include "bme280.h" +#include "arduino.h" +#include + +Adafruit_BME280 theBME280; +Adafruit_BME280_Temp bm280TempSensor; +Adafruit_BME280_Pressure bm280PressureSensor; +Adafruit_BME280_Humidity bm280HumiditySensor; + + + +/*! + * @brief class constructor + */ +Adafruit_BME280::Adafruit_BME280() { + t_fine_adjust = 0; + temp_sensor = &bm280TempSensor; + pressure_sensor = &bm280PressureSensor; + humidity_sensor = &bm280HumiditySensor; +} + +// /*! +// * @brief class constructor if using hardware SPI +// * @param cspin the chip select pin to use +// * @param *theSPI +// * optional SPI object +// */ +// Adafruit_BME280::Adafruit_BME280(int8_t cspin, SPIClass *theSPI) { +// spi_dev = new Adafruit_SPIDevice(cspin, 1000000, SPI_BITORDER_MSBFIRST, +// SPI_MODE0, theSPI); +// } + +/*! + * @brief Initialise sensor with given parameters / settings + * @param addr the I2C address the device can be found on + * @param theWire the I2C object to use, defaults to &Wire + * @returns true on success, false otherwise + */ +bool Adafruit_BME280::begin (uint8_t addr) { + if (!i2c_dev->begin()) { + return false; + } + return init(); +} + +/*! + * @brief Initialise sensor with given parameters / settings + * @returns true on success, false otherwise + */ +bool Adafruit_BME280::init() { + // check if sensor, i.e. the chip ID is correct + _sensorID = read8(BME280_REGISTER_CHIPID); + if (_sensorID != 0x60) + return false; + + // reset the device using soft-reset + // this makes sure the IIR is off, etc. + write8(BME280_REGISTER_SOFTRESET, 0xB6); + + // wait for chip to wake up. + _delay_ms(10); + + // if chip is still reading calibration, delay + while (isReadingCalibration()) + _delay_ms(10); + + readCoefficients(); // read trimming parameters, see DS 4.2.2 + + setSampling(); // use defaults + + _delay_ms(100); + + return true; +} + +/*! + * @brief setup sensor with given parameters / settings + * + * This is simply a overload to the normal begin()-function, so SPI users + * don't get confused about the library requiring an address. + * @param mode the power mode to use for the sensor + * @param tempSampling the temp samping rate to use + * @param pressSampling the pressure sampling rate to use + * @param humSampling the humidity sampling rate to use + * @param filter the filter mode to use + * @param duration the standby duration to use + */ +void Adafruit_BME280::setSampling(sensor_mode mode, + sensor_sampling tempSampling, + sensor_sampling pressSampling, + sensor_sampling humSampling, + sensor_filter filter, + standby_duration duration) { + _measReg.mode = mode; + _measReg.osrs_t = tempSampling; + _measReg.osrs_p = pressSampling; + + _humReg.osrs_h = humSampling; + _configReg.filter = filter; + _configReg.t_sb = duration; + _configReg.spi3w_en = 0; + + // making sure sensor is in sleep mode before setting configuration + // as it otherwise may be ignored + write8(BME280_REGISTER_CONTROL, MODE_SLEEP); + + // you must make sure to also set REGISTER_CONTROL after setting the + // CONTROLHUMID register, otherwise the values won't be applied (see + // DS 5.4.3) + write8(BME280_REGISTER_CONTROLHUMID, _humReg.get()); + write8(BME280_REGISTER_CONFIG, _configReg.get()); + write8(BME280_REGISTER_CONTROL, _measReg.get()); +} + +/*! + * @brief Writes an 8 bit value over I2C or SPI + * @param reg the register address to write to + * @param value the value to write to the register + */ +void Adafruit_BME280::write8(byte reg, byte value) { + byte buffer[2]; + buffer[1] = value; + if (i2c_dev) { + buffer[0] = reg; + i2c_dev->write(buffer, 2); + } +} + +/*! + * @brief Reads an 8 bit value over I2C or SPI + * @param reg the register address to read from + * @returns the data byte read from the device + */ +uint8_t Adafruit_BME280::read8(byte reg) { + uint8_t buffer[1]; + if (i2c_dev) { + buffer[0] = uint8_t(reg); + i2c_dev->write_then_read(buffer, 1, buffer, 1); + } + return buffer[0]; +} + +/*! + * @brief Reads a 16 bit value over I2C or SPI + * @param reg the register address to read from + * @returns the 16 bit data value read from the device + */ +uint16_t Adafruit_BME280::read16(byte reg) { + uint8_t buffer[2]; + + if (i2c_dev) { + buffer[0] = uint8_t(reg); + i2c_dev->write_then_read(buffer, 1, buffer, 2); + } + return uint16_t(buffer[0]) << 8 | uint16_t(buffer[1]); +} + +/*! + * @brief Reads a signed 16 bit little endian value over I2C or SPI + * @param reg the register address to read from + * @returns the 16 bit data value read from the device + */ +uint16_t Adafruit_BME280::read16_LE(byte reg) { + uint16_t temp = read16(reg); + return (temp >> 8) | (temp << 8); +} + +/*! + * @brief Reads a signed 16 bit value over I2C or SPI + * @param reg the register address to read from + * @returns the 16 bit data value read from the device + */ +int16_t Adafruit_BME280::readS16(byte reg) { return (int16_t)read16(reg); } + +/*! + * @brief Reads a signed little endian 16 bit value over I2C or SPI + * @param reg the register address to read from + * @returns the 16 bit data value read from the device + */ +int16_t Adafruit_BME280::readS16_LE(byte reg) { + return (int16_t)read16_LE(reg); +} + +/*! + * @brief Reads a 24 bit value over I2C + * @param reg the register address to read from + * @returns the 24 bit data value read from the device + */ +uint32_t Adafruit_BME280::read24(byte reg) { + uint8_t buffer[3]; + + if (i2c_dev) { + buffer[0] = uint8_t(reg); + i2c_dev->write_then_read(buffer, 1, buffer, 3); + } + return uint32_t(buffer[0]) << 16 | uint32_t(buffer[1]) << 8 | + uint32_t(buffer[2]); +} + +/*! + * @brief Take a new measurement (only possible in forced mode) + @returns true in case of success else false + */ +bool Adafruit_BME280::takeForcedMeasurement(void) { + bool return_value = false; + // If we are in forced mode, the BME sensor goes back to sleep after each + // measurement and we need to set it to forced mode once at this point, so + // it will take the next measurement and then return to sleep again. + // In normal mode simply does new measurements periodically. + if (_measReg.mode == MODE_FORCED) { + return_value = true; + // set to forced mode, i.e. "take next measurement" + write8(BME280_REGISTER_CONTROL, _measReg.get()); + // Store current time to measure the timeout + uint32_t timeout_start = millis(); + // wait until measurement has been completed, otherwise we would read the + // the values from the last measurement or the timeout occurred after 2 sec. + while (read8(BME280_REGISTER_STATUS) & 0x08) { + // In case of a timeout, stop the while loop + if ((millis() - timeout_start) > 2000) { + return_value = false; + break; + } + _delay_ms(1); + } + } + return return_value; +} + +/*! + * @brief Reads the factory-set coefficients + */ +void Adafruit_BME280::readCoefficients(void) { + _bme280_calib.dig_T1 = read16_LE(BME280_REGISTER_DIG_T1); + _bme280_calib.dig_T2 = readS16_LE(BME280_REGISTER_DIG_T2); + _bme280_calib.dig_T3 = readS16_LE(BME280_REGISTER_DIG_T3); + + _bme280_calib.dig_P1 = read16_LE(BME280_REGISTER_DIG_P1); + _bme280_calib.dig_P2 = readS16_LE(BME280_REGISTER_DIG_P2); + _bme280_calib.dig_P3 = readS16_LE(BME280_REGISTER_DIG_P3); + _bme280_calib.dig_P4 = readS16_LE(BME280_REGISTER_DIG_P4); + _bme280_calib.dig_P5 = readS16_LE(BME280_REGISTER_DIG_P5); + _bme280_calib.dig_P6 = readS16_LE(BME280_REGISTER_DIG_P6); + _bme280_calib.dig_P7 = readS16_LE(BME280_REGISTER_DIG_P7); + _bme280_calib.dig_P8 = readS16_LE(BME280_REGISTER_DIG_P8); + _bme280_calib.dig_P9 = readS16_LE(BME280_REGISTER_DIG_P9); + + _bme280_calib.dig_H1 = read8(BME280_REGISTER_DIG_H1); + _bme280_calib.dig_H2 = readS16_LE(BME280_REGISTER_DIG_H2); + _bme280_calib.dig_H3 = read8(BME280_REGISTER_DIG_H3); + _bme280_calib.dig_H4 = ((int8_t)read8(BME280_REGISTER_DIG_H4) << 4) | + (read8(BME280_REGISTER_DIG_H4 + 1) & 0xF); + _bme280_calib.dig_H5 = ((int8_t)read8(BME280_REGISTER_DIG_H5 + 1) << 4) | + (read8(BME280_REGISTER_DIG_H5) >> 4); + _bme280_calib.dig_H6 = (int8_t)read8(BME280_REGISTER_DIG_H6); +} + +/*! + * @brief return true if chip is busy reading cal data + * @returns true if reading calibration, false otherwise + */ +bool Adafruit_BME280::isReadingCalibration(void) { + uint8_t const rStatus = read8(BME280_REGISTER_STATUS); + + return (rStatus & (1 << 0)) != 0; +} + +/*! + * @brief Returns the temperature from the sensor + * @returns the temperature read from the device + */ +float Adafruit_BME280::readTemperature(void) { + int32_t var1, var2; + + int32_t adc_T = read24(BME280_REGISTER_TEMPDATA); + if (adc_T == 0x800000) // value in case temp measurement was disabled + return NAN; + adc_T >>= 4; + + var1 = (int32_t)((adc_T / 8) - ((int32_t)_bme280_calib.dig_T1 * 2)); + var1 = (var1 * ((int32_t)_bme280_calib.dig_T2)) / 2048; + var2 = (int32_t)((adc_T / 16) - ((int32_t)_bme280_calib.dig_T1)); + var2 = (((var2 * var2) / 4096) * ((int32_t)_bme280_calib.dig_T3)) / 16384; + + t_fine = var1 + var2 + t_fine_adjust; + + int32_t T = (t_fine * 5 + 128) / 256; + + return (float)T / 100; +} + +/*! + * @brief Returns the pressure from the sensor + * @returns the pressure value (in Pascal) read from the device + */ +float Adafruit_BME280::readPressure(void) { + int64_t var1, var2, var3, var4; + + readTemperature(); // must be done first to get t_fine + + int32_t adc_P = read24(BME280_REGISTER_PRESSUREDATA); + if (adc_P == 0x800000) // value in case pressure measurement was disabled + return NAN; + adc_P >>= 4; + + var1 = ((int64_t)t_fine) - 128000; + var2 = var1 * var1 * (int64_t)_bme280_calib.dig_P6; + var2 = var2 + ((var1 * (int64_t)_bme280_calib.dig_P5) * 131072); + var2 = var2 + (((int64_t)_bme280_calib.dig_P4) * 34359738368); + var1 = ((var1 * var1 * (int64_t)_bme280_calib.dig_P3) / 256) + + ((var1 * ((int64_t)_bme280_calib.dig_P2) * 4096)); + var3 = ((int64_t)1) * 140737488355328; + var1 = (var3 + var1) * ((int64_t)_bme280_calib.dig_P1) / 8589934592; + + if (var1 == 0) { + return 0; // avoid exception caused by division by zero + } + + var4 = 1048576 - adc_P; + var4 = (((var4 * 2147483648UL) - var2) * 3125) / var1; + var1 = (((int64_t)_bme280_calib.dig_P9) * (var4 / 8192) * (var4 / 8192)) / + 33554432; + var2 = (((int64_t)_bme280_calib.dig_P8) * var4) / 524288; + var4 = ((var4 + var1 + var2) / 256) + (((int64_t)_bme280_calib.dig_P7) * 16); + + float P = var4 / 256.0; + + return P; +} + +/*! + * @brief Returns the humidity from the sensor + * @returns the humidity value read from the device + */ +float Adafruit_BME280::readHumidity(void) { + int32_t var1, var2, var3, var4, var5; + + readTemperature(); // must be done first to get t_fine + + int32_t adc_H = read16(BME280_REGISTER_HUMIDDATA); + if (adc_H == 0x8000) // value in case humidity measurement was disabled + return NAN; + + var1 = t_fine - ((int32_t)76800); + var2 = (int32_t)(adc_H * 16384); + var3 = (int32_t)(((int32_t)_bme280_calib.dig_H4) * 1048576); + var4 = ((int32_t)_bme280_calib.dig_H5) * var1; + var5 = (((var2 - var3) - var4) + (int32_t)16384) / 32768; + var2 = (var1 * ((int32_t)_bme280_calib.dig_H6)) / 1024; + var3 = (var1 * ((int32_t)_bme280_calib.dig_H3)) / 2048; + var4 = ((var2 * (var3 + (int32_t)32768)) / 1024) + (int32_t)2097152; + var2 = ((var4 * ((int32_t)_bme280_calib.dig_H2)) + 8192) / 16384; + var3 = var5 * var2; + var4 = ((var3 / 32768) * (var3 / 32768)) / 128; + var5 = var3 - ((var4 * ((int32_t)_bme280_calib.dig_H1)) / 16); + var5 = (var5 < 0 ? 0 : var5); + var5 = (var5 > 419430400 ? 419430400 : var5); + uint32_t H = (uint32_t)(var5 / 4096); + + return (float)H / 1024.0; +} + +/*! + * Calculates the altitude (in meters) from the specified atmospheric + * pressure (in hPa), and sea-level pressure (in hPa). + * @param seaLevel Sea-level pressure in hPa + * @returns the altitude value read from the device + */ +float Adafruit_BME280::readAltitude(float seaLevel) { + // Equation taken from BMP180 datasheet (page 16): + // http://www.adafruit.com/datasheets/BST-BMP180-DS000-09.pdf + + // Note that using the equation from wikipedia can give bad results + // at high altitude. See this thread for more information: + // http://forums.adafruit.com/viewtopic.php?f=22&t=58064 + + float atmospheric = readPressure() / 100.0F; + return 44330.0 * (1.0 - pow(atmospheric / seaLevel, 0.1903)); +} + +/*! + * Calculates the pressure at sea level (in hPa) from the specified + * altitude (in meters), and atmospheric pressure (in hPa). + * @param altitude Altitude in meters + * @param atmospheric Atmospheric pressure in hPa + * @returns the pressure at sea level (in hPa) from the specified altitude + */ +float Adafruit_BME280::seaLevelForAltitude(float altitude, float atmospheric) { + // Equation taken from BMP180 datasheet (page 17): + // http://www.adafruit.com/datasheets/BST-BMP180-DS000-09.pdf + + // Note that using the equation from wikipedia can give bad results + // at high altitude. See this thread for more information: + // http://forums.adafruit.com/viewtopic.php?f=22&t=58064 + + return atmospheric / pow(1.0 - (altitude / 44330.0), 5.255); +} + +/*! + * Returns Sensor ID found by init() for diagnostics + * @returns Sensor ID 0x60 for BME280, 0x56, 0x57, 0x58 BMP280 + */ +uint32_t Adafruit_BME280::sensorID(void) { return _sensorID; } + +/*! + * Returns the current temperature compensation value in degrees Celsius + * @returns the current temperature compensation value in degrees Celsius + */ +float Adafruit_BME280::getTemperatureCompensation(void) { + return float((t_fine_adjust * 5) >> 8) / 100.0; +}; + +/*! + * Sets a value to be added to each temperature reading. This adjusted + * temperature is used in pressure and humidity readings. + * @param adjustment Value to be added to each temperature reading in Celsius + */ +void Adafruit_BME280::setTemperatureCompensation(float adjustment) { + // convert the value in C into and adjustment to t_fine + t_fine_adjust = ((int32_t(adjustment * 100) << 8)) / 5; +}; + + +/**************************************************************************/ +/*! + @brief Gets the sensor_t data for the BME280's temperature sensor +*/ +/**************************************************************************/ +void Adafruit_BME280_Temp::getSensor(sensor_t *sensor) { + /* Clear the sensor_t object */ + memset(sensor, 0, sizeof(sensor_t)); + + /* Insert the sensor name in the fixed length char array */ + strncpy(sensor->name, "BME280", sizeof(sensor->name) - 1); + sensor->name[sizeof(sensor->name) - 1] = 0; + sensor->version = 1; + sensor->sensor_id = _sensorID; + sensor->type = SENSOR_TYPE_AMBIENT_TEMPERATURE; + sensor->min_delay = 0; + sensor->min_value = -40.0; /* Temperature range -40 ~ +85 C */ + sensor->max_value = +85.0; + sensor->resolution = 0.01; /* 0.01 C */ +} + +/**************************************************************************/ +/*! + @brief Gets the temperature as a standard sensor event + @param event Sensor event object that will be populated + @returns True +*/ +/**************************************************************************/ +bool Adafruit_BME280_Temp::getEvent(sensors_event_t *event) { + /* Clear the event */ + memset(event, 0, sizeof(sensors_event_t)); + + event->version = sizeof(sensors_event_t); + event->sensor_id = _sensorID; + event->type = SENSOR_TYPE_AMBIENT_TEMPERATURE; + event->timestamp = millis(); + event->temperature = theBME280.readTemperature(); + return true; +} + +/**************************************************************************/ +/*! + @brief Gets the sensor_t data for the BME280's pressure sensor +*/ +/**************************************************************************/ +void Adafruit_BME280_Pressure::getSensor(sensor_t *sensor) { + /* Clear the sensor_t object */ + memset(sensor, 0, sizeof(sensor_t)); + + /* Insert the sensor name in the fixed length char array */ + strncpy(sensor->name, "BME280", sizeof(sensor->name) - 1); + sensor->name[sizeof(sensor->name) - 1] = 0; + sensor->version = 1; + sensor->sensor_id = _sensorID; + sensor->type = SENSOR_TYPE_PRESSURE; + sensor->min_delay = 0; + sensor->min_value = 300.0; /* 300 ~ 1100 hPa */ + sensor->max_value = 1100.0; + sensor->resolution = 0.012; /* 0.12 hPa relative */ +} + +/**************************************************************************/ +/*! + @brief Gets the pressure as a standard sensor event + @param event Sensor event object that will be populated + @returns True +*/ +/**************************************************************************/ +bool Adafruit_BME280_Pressure::getEvent(sensors_event_t *event) { + /* Clear the event */ + memset(event, 0, sizeof(sensors_event_t)); + + event->version = sizeof(sensors_event_t); + event->sensor_id = _sensorID; + event->type = SENSOR_TYPE_PRESSURE; + event->timestamp = millis(); + event->pressure = theBME280.readPressure() / 100; // convert Pa to hPa + return true; +} + +/**************************************************************************/ +/*! + @brief Gets the sensor_t data for the BME280's humidity sensor +*/ +/**************************************************************************/ +void Adafruit_BME280_Humidity::getSensor(sensor_t *sensor) { + /* Clear the sensor_t object */ + memset(sensor, 0, sizeof(sensor_t)); + + /* Insert the sensor name in the fixed length char array */ + strncpy(sensor->name, "BME280", sizeof(sensor->name) - 1); + sensor->name[sizeof(sensor->name) - 1] = 0; + sensor->version = 1; + sensor->sensor_id = _sensorID; + sensor->type = SENSOR_TYPE_RELATIVE_HUMIDITY; + sensor->min_delay = 0; + sensor->min_value = 0; + sensor->max_value = 100; /* 0 - 100 % */ + sensor->resolution = 3; /* 3% accuracy */ +} + +/**************************************************************************/ +/*! + @brief Gets the humidity as a standard sensor event + @param event Sensor event object that will be populated + @returns True +*/ +/**************************************************************************/ +bool Adafruit_BME280_Humidity::getEvent(sensors_event_t *event) { + /* Clear the event */ + memset(event, 0, sizeof(sensors_event_t)); + + event->version = sizeof(sensors_event_t); + event->sensor_id = _sensorID; + event->type = SENSOR_TYPE_RELATIVE_HUMIDITY; + event->timestamp = millis(); + event->relative_humidity = theBME280.readHumidity(); + return true; +} diff --git a/software/test_2024-07-23/src/adafruit/bme280.h b/software/test_2024-07-23/src/adafruit/bme280.h new file mode 100644 index 0000000..dd59f79 --- /dev/null +++ b/software/test_2024-07-23/src/adafruit/bme280.h @@ -0,0 +1,368 @@ +// https://github.com/adafruit/Adafruit_BME280_Library + +/*! + * @file Adafruit_BME280.h + * + * Designed specifically to work with the Adafruit BME280 Breakout + * ----> http://www.adafruit.com/products/2650 + * + * These sensors use I2C or SPI to communicate, 2 or 4 pins are required + * to interface. + * + * Adafruit invests time and resources providing this open source code, + * please support Adafruit and open-source hardware by purchasing + * products from Adafruit! + * + * Written by Kevin "KTOWN" Townsend for Adafruit Industries. + * + * BSD license, all text here must be included in any redistribution. + * See the LICENSE file for details. + * + */ + +#ifndef __BME280_H__ +#define __BME280_H__ + +// #include "Arduino.h" + +// #include +// #include +// #include + + +#include +#include +#include "arduino.h" +#include "sensor.h" + +/*! + * @brief default I2C address + */ +#define BME280_ADDRESS (0x77) // Primary I2C Address + /*! + * @brief alternate I2C address + */ +#define BME280_ADDRESS_ALTERNATE (0x76) // Alternate Address + +/*! + * @brief Register addresses + */ +enum { + BME280_REGISTER_DIG_T1 = 0x88, + BME280_REGISTER_DIG_T2 = 0x8A, + BME280_REGISTER_DIG_T3 = 0x8C, + + BME280_REGISTER_DIG_P1 = 0x8E, + BME280_REGISTER_DIG_P2 = 0x90, + BME280_REGISTER_DIG_P3 = 0x92, + BME280_REGISTER_DIG_P4 = 0x94, + BME280_REGISTER_DIG_P5 = 0x96, + BME280_REGISTER_DIG_P6 = 0x98, + BME280_REGISTER_DIG_P7 = 0x9A, + BME280_REGISTER_DIG_P8 = 0x9C, + BME280_REGISTER_DIG_P9 = 0x9E, + + BME280_REGISTER_DIG_H1 = 0xA1, + BME280_REGISTER_DIG_H2 = 0xE1, + BME280_REGISTER_DIG_H3 = 0xE3, + BME280_REGISTER_DIG_H4 = 0xE4, + BME280_REGISTER_DIG_H5 = 0xE5, + BME280_REGISTER_DIG_H6 = 0xE7, + + BME280_REGISTER_CHIPID = 0xD0, + BME280_REGISTER_VERSION = 0xD1, + BME280_REGISTER_SOFTRESET = 0xE0, + + BME280_REGISTER_CAL26 = 0xE1, // R calibration stored in 0xE1-0xF0 + + BME280_REGISTER_CONTROLHUMID = 0xF2, + BME280_REGISTER_STATUS = 0XF3, + BME280_REGISTER_CONTROL = 0xF4, + BME280_REGISTER_CONFIG = 0xF5, + BME280_REGISTER_PRESSUREDATA = 0xF7, + BME280_REGISTER_TEMPDATA = 0xFA, + BME280_REGISTER_HUMIDDATA = 0xFD +}; + +/**************************************************************************/ +/*! + @brief calibration data +*/ +/**************************************************************************/ +typedef struct { + uint16_t dig_T1; ///< temperature compensation value + int16_t dig_T2; ///< temperature compensation value + int16_t dig_T3; ///< temperature compensation value + + uint16_t dig_P1; ///< pressure compensation value + int16_t dig_P2; ///< pressure compensation value + int16_t dig_P3; ///< pressure compensation value + int16_t dig_P4; ///< pressure compensation value + int16_t dig_P5; ///< pressure compensation value + int16_t dig_P6; ///< pressure compensation value + int16_t dig_P7; ///< pressure compensation value + int16_t dig_P8; ///< pressure compensation value + int16_t dig_P9; ///< pressure compensation value + + uint8_t dig_H1; ///< humidity compensation value + int16_t dig_H2; ///< humidity compensation value + uint8_t dig_H3; ///< humidity compensation value + int16_t dig_H4; ///< humidity compensation value + int16_t dig_H5; ///< humidity compensation value + int8_t dig_H6; ///< humidity compensation value +} bme280_calib_data; +/*=========================================================================*/ + +class Adafruit_BME280; + +/** Adafruit Unified Sensor interface for temperature component of BME280 */ +class Adafruit_BME280_Temp : public Adafruit_Sensor { +public: + /** @brief Create an Adafruit_Sensor compatible object for the temp sensor + @param parent A pointer to the BME280 class */ + Adafruit_BME280_Temp() { _sensorID = 280; } + bool getEvent(sensors_event_t *); + void getSensor(sensor_t *); + +private: + int _sensorID; +}; + +/** Adafruit Unified Sensor interface for pressure component of BME280 */ +class Adafruit_BME280_Pressure : public Adafruit_Sensor { +public: + /** @brief Create an Adafruit_Sensor compatible object for the pressure sensor + @param parent A pointer to the BME280 class */ + Adafruit_BME280_Pressure() { _sensorID = 280; } + bool getEvent(sensors_event_t *); + void getSensor(sensor_t *); + +private: + int _sensorID; +}; + +/** Adafruit Unified Sensor interface for humidity component of BME280 */ +class Adafruit_BME280_Humidity : public Adafruit_Sensor { +public: + /** @brief Create an Adafruit_Sensor compatible object for the humidity sensor + @param parent A pointer to the BME280 class */ + Adafruit_BME280_Humidity() { _sensorID = 280;} + bool getEvent(sensors_event_t *); + void getSensor(sensor_t *); + +private: + int _sensorID; +}; + +/**************************************************************************/ +/*! + @brief Class that stores state and functions for interacting with BME280 IC +*/ +/**************************************************************************/ +class Adafruit_BME280 { +public: + /**************************************************************************/ + /*! + @brief sampling rates + */ + /**************************************************************************/ + enum sensor_sampling { + SAMPLING_NONE = 0b000, + SAMPLING_X1 = 0b001, + SAMPLING_X2 = 0b010, + SAMPLING_X4 = 0b011, + SAMPLING_X8 = 0b100, + SAMPLING_X16 = 0b101 + }; + + /**************************************************************************/ + /*! + @brief power modes + */ + /**************************************************************************/ + enum sensor_mode { + MODE_SLEEP = 0b00, + MODE_FORCED = 0b01, + MODE_NORMAL = 0b11 + }; + + /**************************************************************************/ + /*! + @brief filter values + */ + /**************************************************************************/ + enum sensor_filter { + FILTER_OFF = 0b000, + FILTER_X2 = 0b001, + FILTER_X4 = 0b010, + FILTER_X8 = 0b011, + FILTER_X16 = 0b100 + }; + + /**************************************************************************/ + /*! + @brief standby duration in ms + */ + /**************************************************************************/ + enum standby_duration { + STANDBY_MS_0_5 = 0b000, + STANDBY_MS_10 = 0b110, + STANDBY_MS_20 = 0b111, + STANDBY_MS_62_5 = 0b001, + STANDBY_MS_125 = 0b010, + STANDBY_MS_250 = 0b011, + STANDBY_MS_500 = 0b100, + STANDBY_MS_1000 = 0b101 + }; + + // constructors + Adafruit_BME280(); + + bool begin(uint8_t addr = BME280_ADDRESS); + bool init(); + + void setSampling(sensor_mode mode = MODE_NORMAL, + sensor_sampling tempSampling = SAMPLING_X16, + sensor_sampling pressSampling = SAMPLING_X16, + sensor_sampling humSampling = SAMPLING_X16, + sensor_filter filter = FILTER_OFF, + standby_duration duration = STANDBY_MS_0_5); + + bool takeForcedMeasurement(void); + float readTemperature(void); + float readPressure(void); + float readHumidity(void); + + float readAltitude(float seaLevel); + float seaLevelForAltitude(float altitude, float pressure); + uint32_t sensorID(void); + + float getTemperatureCompensation(void); + void setTemperatureCompensation(float); + +protected: + Adafruit_I2CDevice *i2c_dev = NULL; ///< Pointer to I2C bus interface + Adafruit_SPIDevice *spi_dev = NULL; ///< Pointer to SPI bus interface + + Adafruit_BME280_Temp *temp_sensor; + Adafruit_BME280_Pressure *pressure_sensor; + Adafruit_BME280_Humidity *humidity_sensor; + + void readCoefficients(void); + bool isReadingCalibration(void); + + void write8(byte reg, byte value); + uint8_t read8(byte reg); + uint16_t read16(byte reg); + uint32_t read24(byte reg); + int16_t readS16(byte reg); + uint16_t read16_LE(byte reg); // little endian + int16_t readS16_LE(byte reg); // little endian + + uint8_t _i2caddr; //!< I2C addr for the TwoWire interface + int32_t _sensorID; //!< ID of the BME Sensor + int32_t t_fine; //!< temperature with high resolution, stored as an attribute + //!< as this is used for temperature compensation reading + //!< humidity and pressure + + int32_t t_fine_adjust; //!< add to compensate temp readings and in turn + //!< to pressure and humidity readings + + bme280_calib_data _bme280_calib; //!< here calibration data is stored + + /**************************************************************************/ + /*! + @brief config register + */ + /**************************************************************************/ + struct config { + // inactive duration (standby time) in normal mode + // 000 = 0.5 ms + // 001 = 62.5 ms + // 010 = 125 ms + // 011 = 250 ms + // 100 = 500 ms + // 101 = 1000 ms + // 110 = 10 ms + // 111 = 20 ms + unsigned int t_sb : 3; ///< inactive duration (standby time) in normal mode + + // filter settings + // 000 = filter off + // 001 = 2x filter + // 010 = 4x filter + // 011 = 8x filter + // 100 and above = 16x filter + unsigned int filter : 3; ///< filter settings + + // unused - don't set + unsigned int none : 1; ///< unused - don't set + unsigned int spi3w_en : 1; ///< unused - don't set + + /// @return combined config register + unsigned int get() { return (t_sb << 5) | (filter << 2) | spi3w_en; } + }; + config _configReg; //!< config register object + + /**************************************************************************/ + /*! + @brief ctrl_meas register + */ + /**************************************************************************/ + struct ctrl_meas { + // temperature oversampling + // 000 = skipped + // 001 = x1 + // 010 = x2 + // 011 = x4 + // 100 = x8 + // 101 and above = x16 + unsigned int osrs_t : 3; ///< temperature oversampling + + // pressure oversampling + // 000 = skipped + // 001 = x1 + // 010 = x2 + // 011 = x4 + // 100 = x8 + // 101 and above = x16 + unsigned int osrs_p : 3; ///< pressure oversampling + + // device mode + // 00 = sleep + // 01 or 10 = forced + // 11 = normal + unsigned int mode : 2; ///< device mode + + /// @return combined ctrl register + unsigned int get() { return (osrs_t << 5) | (osrs_p << 2) | mode; } + }; + ctrl_meas _measReg; //!< measurement register object + + /**************************************************************************/ + /*! + @brief ctrl_hum register + */ + /**************************************************************************/ + struct ctrl_hum { + /// unused - don't set + unsigned int none : 5; + + // pressure oversampling + // 000 = skipped + // 001 = x1 + // 010 = x2 + // 011 = x4 + // 100 = x8 + // 101 and above = x16 + unsigned int osrs_h : 3; ///< pressure oversampling + + /// @return combined ctrl hum register + unsigned int get() { return (osrs_h); } + }; + ctrl_hum _humReg; //!< hum register object +}; + +extern Adafruit_BME280 theBME280; + +#endif diff --git a/software/test_2024-07-23/src/adafruit/sensor.cpp b/software/test_2024-07-23/src/adafruit/sensor.cpp new file mode 100644 index 0000000..c180fd1 --- /dev/null +++ b/software/test_2024-07-23/src/adafruit/sensor.cpp @@ -0,0 +1,123 @@ +// https://github.com/adafruit/Adafruit_Sensor + +// #include "Adafruit_Sensor.h" +#include "sensor.h" + +/**************************************************************************/ +/*! + @brief Prints sensor information to serial console +*/ +/**************************************************************************/ +void Adafruit_Sensor::printSensorDetails(void) { +// sensor_t sensor; +// getSensor(&sensor); +// Serial.println(F("------------------------------------")); +// Serial.print(F("Sensor: ")); +// Serial.println(sensor.name); +// Serial.print(F("Type: ")); +// switch ((sensors_type_t)sensor.type) { +// case SENSOR_TYPE_ACCELEROMETER: +// Serial.print(F("Acceleration (m/s2)")); +// break; +// case SENSOR_TYPE_MAGNETIC_FIELD: +// Serial.print(F("Magnetic (uT)")); +// break; +// case SENSOR_TYPE_ORIENTATION: +// Serial.print(F("Orientation (degrees)")); +// break; +// case SENSOR_TYPE_GYROSCOPE: +// Serial.print(F("Gyroscopic (rad/s)")); +// break; +// case SENSOR_TYPE_LIGHT: +// Serial.print(F("Light (lux)")); +// break; +// case SENSOR_TYPE_PRESSURE: +// Serial.print(F("Pressure (hPa)")); +// break; +// case SENSOR_TYPE_PROXIMITY: +// Serial.print(F("Distance (cm)")); +// break; +// case SENSOR_TYPE_GRAVITY: +// Serial.print(F("Gravity (m/s2)")); +// break; +// case SENSOR_TYPE_LINEAR_ACCELERATION: +// Serial.print(F("Linear Acceleration (m/s2)")); +// break; +// case SENSOR_TYPE_ROTATION_VECTOR: +// Serial.print(F("Rotation vector")); +// break; +// case SENSOR_TYPE_RELATIVE_HUMIDITY: +// Serial.print(F("Relative Humidity (%)")); +// break; +// case SENSOR_TYPE_AMBIENT_TEMPERATURE: +// Serial.print(F("Ambient Temp (C)")); +// break; +// case SENSOR_TYPE_OBJECT_TEMPERATURE: +// Serial.print(F("Object Temp (C)")); +// break; +// case SENSOR_TYPE_VOLTAGE: +// Serial.print(F("Voltage (V)")); +// break; +// case SENSOR_TYPE_CURRENT: +// Serial.print(F("Current (mA)")); +// break; +// case SENSOR_TYPE_COLOR: +// Serial.print(F("Color (RGBA)")); +// break; +// case SENSOR_TYPE_TVOC: +// Serial.print(F("Total Volatile Organic Compounds (ppb)")); +// break; +// case SENSOR_TYPE_VOC_INDEX: +// Serial.print(F("Volatile Organic Compounds (Index)")); +// break; +// case SENSOR_TYPE_NOX_INDEX: +// Serial.print(F("Nitrogen Oxides (Index)")); +// break; +// case SENSOR_TYPE_CO2: +// Serial.print(F("Carbon Dioxide (ppm)")); +// break; +// case SENSOR_TYPE_ECO2: +// Serial.print(F("Equivalent/estimated CO2 (ppm)")); +// break; +// case SENSOR_TYPE_PM10_STD: +// Serial.print(F("Standard Particulate Matter 1.0 (ppm)")); +// break; +// case SENSOR_TYPE_PM25_STD: +// Serial.print(F("Standard Particulate Matter 2.5 (ppm)")); +// break; +// case SENSOR_TYPE_PM100_STD: +// Serial.print(F("Standard Particulate Matter 10.0 (ppm)")); +// break; +// case SENSOR_TYPE_PM10_ENV: +// Serial.print(F("Environmental Particulate Matter 1.0 (ppm)")); +// break; +// case SENSOR_TYPE_PM25_ENV: +// Serial.print(F("Environmental Particulate Matter 2.5 (ppm)")); +// break; +// case SENSOR_TYPE_PM100_ENV: +// Serial.print(F("Environmental Particulate Matter 10.0 (ppm)")); +// break; +// case SENSOR_TYPE_GAS_RESISTANCE: +// Serial.print(F("Gas Resistance (ohms)")); +// break; +// case SENSOR_TYPE_UNITLESS_PERCENT: +// Serial.print(F("Unitless Percent (%)")); +// break; +// case SENSOR_TYPE_ALTITUDE: +// Serial.print(F("Altitude (m)")); +// break; +// } + +// Serial.println(); +// Serial.print(F("Driver Ver: ")); +// Serial.println(sensor.version); +// Serial.print(F("Unique ID: ")); +// Serial.println(sensor.sensor_id); +// Serial.print(F("Min Value: ")); +// Serial.println(sensor.min_value); +// Serial.print(F("Max Value: ")); +// Serial.println(sensor.max_value); +// Serial.print(F("Resolution: ")); +// Serial.println(sensor.resolution); +// Serial.println(F("------------------------------------\n")); +} diff --git a/software/test_2024-07-23/src/adafruit/sensor.h b/software/test_2024-07-23/src/adafruit/sensor.h new file mode 100644 index 0000000..72cf981 --- /dev/null +++ b/software/test_2024-07-23/src/adafruit/sensor.h @@ -0,0 +1,225 @@ +// https://github.com/adafruit/Adafruit_Sensor + +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software< /span> + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* Update by K. Townsend (Adafruit Industries) for lighter typedefs, and + * extended sensor support to include color, voltage and current */ + +#ifndef _ADAFRUIT_SENSOR_H +#define _ADAFRUIT_SENSOR_H + +#ifndef ARDUINO +#include +#elif ARDUINO >= 100 +#include "Arduino.h" +#include "Print.h" +#else +#include "WProgram.h" +#endif + +/* Constants */ +#define SENSORS_GRAVITY_EARTH (9.80665F) /**< Earth's gravity in m/s^2 */ +#define SENSORS_GRAVITY_MOON (1.6F) /**< The moon's gravity in m/s^2 */ +#define SENSORS_GRAVITY_SUN (275.0F) /**< The sun's gravity in m/s^2 */ +#define SENSORS_GRAVITY_STANDARD (SENSORS_GRAVITY_EARTH) +#define SENSORS_MAGFIELD_EARTH_MAX \ + (60.0F) /**< Maximum magnetic field on Earth's surface */ +#define SENSORS_MAGFIELD_EARTH_MIN \ + (30.0F) /**< Minimum magnetic field on Earth's surface */ +#define SENSORS_PRESSURE_SEALEVELHPA \ + (1013.25F) /**< Average sea level pressure is 1013.25 hPa */ +#define SENSORS_DPS_TO_RADS \ + (0.017453293F) /**< Degrees/s to rad/s multiplier \ + */ +#define SENSORS_RADS_TO_DPS \ + (57.29577793F) /**< Rad/s to degrees/s multiplier */ +#define SENSORS_GAUSS_TO_MICROTESLA \ + (100) /**< Gauss to micro-Tesla multiplier */ + +/** Sensor types */ +typedef enum { + SENSOR_TYPE_ACCELEROMETER = (1), /**< Gravity + linear acceleration */ + SENSOR_TYPE_MAGNETIC_FIELD = (2), + SENSOR_TYPE_ORIENTATION = (3), + SENSOR_TYPE_GYROSCOPE = (4), + SENSOR_TYPE_LIGHT = (5), + SENSOR_TYPE_PRESSURE = (6), + SENSOR_TYPE_PROXIMITY = (8), + SENSOR_TYPE_GRAVITY = (9), + SENSOR_TYPE_LINEAR_ACCELERATION = + (10), /**< Acceleration not including gravity */ + SENSOR_TYPE_ROTATION_VECTOR = (11), + SENSOR_TYPE_RELATIVE_HUMIDITY = (12), + SENSOR_TYPE_AMBIENT_TEMPERATURE = (13), + SENSOR_TYPE_OBJECT_TEMPERATURE = (14), + SENSOR_TYPE_VOLTAGE = (15), + SENSOR_TYPE_CURRENT = (16), + SENSOR_TYPE_COLOR = (17), + SENSOR_TYPE_TVOC = (18), + SENSOR_TYPE_VOC_INDEX = (19), + SENSOR_TYPE_NOX_INDEX = (20), + SENSOR_TYPE_CO2 = (21), + SENSOR_TYPE_ECO2 = (22), + SENSOR_TYPE_PM10_STD = (23), + SENSOR_TYPE_PM25_STD = (24), + SENSOR_TYPE_PM100_STD = (25), + SENSOR_TYPE_PM10_ENV = (26), + SENSOR_TYPE_PM25_ENV = (27), + SENSOR_TYPE_PM100_ENV = (28), + SENSOR_TYPE_GAS_RESISTANCE = (29), + SENSOR_TYPE_UNITLESS_PERCENT = (30), + SENSOR_TYPE_ALTITUDE = (31) +} sensors_type_t; + +/** struct sensors_vec_s is used to return a vector in a common format. */ +typedef struct { + union { + float v[3]; ///< 3D vector elements + struct { + float x; ///< X component of vector + float y; ///< Y component of vector + float z; ///< Z component of vector + }; ///< Struct for holding XYZ component + /* Orientation sensors */ + struct { + float roll; /**< Rotation around the longitudinal axis (the plane body, 'X + axis'). Roll is positive and increasing when moving + downward. -90 degrees <= roll <= 90 degrees */ + float pitch; /**< Rotation around the lateral axis (the wing span, 'Y + axis'). Pitch is positive and increasing when moving + upwards. -180 degrees <= pitch <= 180 degrees) */ + float heading; /**< Angle between the longitudinal axis (the plane body) + and magnetic north, measured clockwise when viewing from + the top of the device. 0-359 degrees */ + }; ///< Struct for holding roll/pitch/heading + }; ///< Union that can hold 3D vector array, XYZ components or + ///< roll/pitch/heading + int8_t status; ///< Status byte + uint8_t reserved[3]; ///< Reserved +} sensors_vec_t; + +/** struct sensors_color_s is used to return color data in a common format. */ +typedef struct { + union { + float c[3]; ///< Raw 3-element data + /* RGB color space */ + struct { + float r; /**< Red component */ + float g; /**< Green component */ + float b; /**< Blue component */ + }; ///< RGB data in floating point notation + }; ///< Union of various ways to describe RGB colorspace + uint32_t rgba; /**< 24-bit RGBA value */ +} sensors_color_t; + +/* Sensor event (36 bytes) */ +/** struct sensor_event_s is used to provide a single sensor event in a common + * format. */ +typedef struct { + int32_t version; /**< must be sizeof(struct sensors_event_t) */ + int32_t sensor_id; /**< unique sensor identifier */ + int32_t type; /**< sensor type */ + int32_t reserved0; /**< reserved */ + int32_t timestamp; /**< time is in milliseconds */ + union { + float data[4]; ///< Raw data */ + sensors_vec_t acceleration; /**< acceleration values are in meter per second + per second (m/s^2) */ + sensors_vec_t + magnetic; /**< magnetic vector values are in micro-Tesla (uT) */ + sensors_vec_t orientation; /**< orientation values are in degrees */ + sensors_vec_t gyro; /**< gyroscope values are in rad/s */ + float temperature; /**< temperature is in degrees centigrade (Celsius) */ + float distance; /**< distance in centimeters */ + float light; /**< light in SI lux units */ + float pressure; /**< pressure in hectopascal (hPa) */ + float relative_humidity; /**< relative humidity in percent */ + float current; /**< current in milliamps (mA) */ + float voltage; /**< voltage in volts (V) */ + float tvoc; /**< Total Volatile Organic Compounds, in ppb */ + float voc_index; /**< VOC (Volatile Organic Compound) index where 100 is + normal (unitless) */ + float nox_index; /**< NOx (Nitrogen Oxides) index where 100 is normal + (unitless) */ + float CO2; /**< Measured CO2 in parts per million (ppm) */ + float eCO2; /**< equivalent/estimated CO2 in parts per million (ppm + estimated from some other measurement) */ + float pm10_std; /**< Standard Particulate Matter <=1.0 in parts per million + (ppm) */ + float pm25_std; /**< Standard Particulate Matter <=2.5 in parts per million + (ppm) */ + float pm100_std; /**< Standard Particulate Matter <=10.0 in parts per + million (ppm) */ + float pm10_env; /**< Environmental Particulate Matter <=1.0 in parts per + million (ppm) */ + float pm25_env; /**< Environmental Particulate Matter <=2.5 in parts per + million (ppm) */ + float pm100_env; /**< Environmental Particulate Matter <=10.0 in parts per + million (ppm) */ + float gas_resistance; /**< Proportional to the amount of VOC particles in + the air (Ohms) */ + float unitless_percent; /** 0) { timer1ms--; } + systemMillis++; } timer500ms++; diff --git a/software/test_2024-07-23/src/main.hpp b/software/test_2024-07-23/src/main.hpp index b7a0735..4490ff3 100644 --- a/software/test_2024-07-23/src/main.hpp +++ b/software/test_2024-07-23/src/main.hpp @@ -8,6 +8,7 @@ extern int wait (uint32_t ms); extern int waitOnKey (char key); +extern uint64_t millis (); class TestUnit { public: diff --git a/software/test_2024-07-23/src/units/i2c.cpp b/software/test_2024-07-23/src/units/i2c.cpp new file mode 100644 index 0000000..9858aa1 --- /dev/null +++ b/software/test_2024-07-23/src/units/i2c.cpp @@ -0,0 +1,264 @@ +#include +#include +#include + +#include "i2c.hpp" +#include "../main.hpp" + + +// Sparkfun https://www.sparkfun.com/products/22858 +// ENS160 address 0x53 (air quality sensor) +// BME280 address 0x77 /humidity/temperature sensor) +// register 0xfe: humidity_7:0 +// register 0xfd: humidity_15:8 + +const char *I2c::getName () { + switch (mode) { + case SparkFunEnvCombo: return "I2C-Sparkfun Env-Combo"; + case Master: return "I2C-Master"; + case Slave: return "I2C-Slave"; + } + return "?"; +} + +void I2c::cleanup () { + enabled = false; + TWCR = (1 << TWEN); + TWBR = 0; +} + +int8_t I2c::run (uint8_t subtest) { + if (subtest == 0) { + TWBR = 13; // 100kHz (TWPS1:0 = 00), TWBR = (F_CPU - 16 * 100000) / (2 * 100000 * 4); + TWBR = 28; // 50kHz (TWPS1:0 = 00), TWBR = (F_CPU - 16 * 50000) / (2 * 50000 * 4); + TWBR = 100; // 50kHz (TWPS1:0 = 00), TWBR = (F_CPU - 16 * 50000) / (2 * 50000 * 4); + TWCR = (1 << TWEN); + enabled = true; + printf("init"); + + } else if (subtest == 1 && mode == SparkFunEnvCombo) { + int key = EOF; + uint8_t buffer[18]; + int errorCode; + while (key == EOF) { + printf("\n => START+WRITE -> "); + errorCode = startWrite(0x77); + if (errorCode > 0) { + stop(); + printf ("ERROR (0x%04x)", errorCode); + continue; + } + printf("OK"); + + printf(", DATA 0xd0 ->"); + errorCode = writeByte(0xd0); + if (errorCode > 0) { + stop(); + printf ("ERROR (0x%04x)", errorCode); + continue; + } + printf("OK"); + + printf("\n => RESTART+READ -> "); + errorCode = startRead(0x77); + if (errorCode > 0) { + stop(); + printf ("ERROR (0x%04x)", errorCode); + continue; + } + printf("OK"); + + printf(", DATA -> "); + errorCode = readData(1, buffer); + if (errorCode > 0) { + stop(); + printf ("ERROR (0x%04x)", errorCode); + continue; + } + printf("OK (%02x %02x)", buffer[0], buffer[1]); + + printf("\n => read trimming -> "); + errorCode = startWrite(0x77); + if (errorCode == 0) { + errorCode = writeByte(0x88); // dig_T1 + errorCode = errorCode != 0 ? 0x1000 | errorCode : 0; + } + if (errorCode == 0) { + errorCode = startRead(0x77); + errorCode = errorCode != 0 ? 0x2000 | errorCode : 0; + } + if (errorCode == 0) { + errorCode = readData(6, buffer); + errorCode = errorCode != 0 ? 0x3000 | errorCode : 0; + } + if (errorCode == 0) { + bm280.digT[0] = ((uint16_t)buffer[1] << 8) | buffer[0]; + bm280.digT[1] = ((uint16_t)buffer[3] << 8) | buffer[2]; + bm280.digT[2] = ((uint16_t)buffer[5] << 8) | buffer[4]; + printf(" T(%04x %04x %04x)", bm280.digT[0], bm280.digT[1], bm280.digT[2]); + } else { + stop(); + printf("ERROR(%04x)", errorCode); + continue; + } + + printf("\n => set ctrl register f2 and f4"); + errorCode = startWrite(0x77); + errorCode = errorCode != 0 ? 0x1000 | errorCode : 0; + if (errorCode == 0) { + errorCode = writeByte(0xf2); // ctl_hum + errorCode = errorCode != 0 ? 0x2000 | errorCode : 0; + } + if (errorCode == 0) { + errorCode = writeByte(0x01); // oversampling x 1 + errorCode = errorCode != 0 ? 0x3000 | errorCode : 0; + } + + if (errorCode == 0) { + errorCode = startWrite(0x77); + errorCode = errorCode != 0 ? 0x4000 | errorCode : 0; + } + if (errorCode == 0) { + errorCode = writeByte(0xf4); // ctl_meas + errorCode = errorCode != 0 ? 0x5000 | errorCode : 0; + } + if (errorCode == 0) { + errorCode = writeByte((3 << 4) | (3 << 2) | 3); // oversampling 1, normal mode + errorCode = errorCode != 0 ? 0x6000 | errorCode : 0; + } + + stop(); + _delay_us(200); + + do { + if (errorCode == 0) { + printf("\n => register 0xf7..0xff:"); + errorCode = startWrite(0x77); + errorCode = errorCode != 0 ? 0x7000 | errorCode : 0; + } + if (errorCode == 0) { + errorCode = writeByte(0xf7); + errorCode = errorCode != 0 ? 0x8000 | errorCode : 0; + } + if (errorCode == 0) { + errorCode = startRead(0x77); + errorCode = errorCode != 0 ? 0x9000 | errorCode : 0; + } + if (errorCode == 0) { + errorCode = readData(8, buffer); + errorCode = errorCode != 0 ? 0xa000 | errorCode : 0; + } + if (errorCode == 0) { + for (uint8_t i = 0; i < 8; i++) { + printf(" %02x", buffer[i]); + } + int32_t adcT = (int32_t)( ((uint32_t)(buffer[3] << 12)) | (uint16_t)(buffer[4] << 4) | (buffer[5] >> 4) ); + int32_t t = compensateBm280T(adcT); + printf(" T=%ld ", t); + } else { + printf("ERROR (%04x)", errorCode); + break; + } + stop(); + key = wait(5000); + } while (key == EOF); + + stop(); + printf("\n"); + + } while (wait(5000) == EOF); + + } else { + printf("end"); + return -1; + } + wait(500); + return 0; +} + +void I2c::handleTwiIrq () { + TWCR |= (1 << TWINT); // clear Interrupt Request +} + +uint16_t I2c::startRead (uint8_t address) { + TWCR = (1 << TWINT) | (1 << TWSTA) | (1 << TWEN); // send START condition + while (!(TWCR & (1 << TWINT))) {}; // wait until last action done + uint8_t sr = TWSR & 0xf8; + if (sr != 0x08 && sr != 0x10) { + return 0x0100 | sr; + } + + TWDR = (address << 1) | 0x01; // address + READ (R/W = 1) + TWCR = (1 << TWINT) | (1 << TWEN); // send address/RW + while (!(TWCR & (1 << TWINT))) {}; // wait until last action done + sr = TWSR & 0xf8; + if (sr != 0x40) { + return 0x0200 | sr; + } + return 0; +} + +uint16_t I2c::startWrite (uint8_t address) { + TWCR = (1 << TWINT) | (1 << TWSTA) | (1 << TWEN); // send START condition + while (!(TWCR & (1 << TWINT))) {}; // wait until last action done + uint8_t sr = TWSR & 0xf8; + if (sr != 0x08 && sr != 0x10) { + return 0x0300 | sr; + } + + TWDR = (address << 1) | 0x00; // address + WRITE (R/W = 0) + TWCR = (1 << TWINT) | (1 << TWEN); // send address/RW + while (!(TWCR & (1 << TWINT))) {}; // wait until last action done + sr = TWSR & 0xf8; + if (sr != 0x18) { + return 0x0400 | sr; + } + return 0; +} + +void I2c::stop () { + TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWSTO); +} + +uint16_t I2c::writeData (uint8_t size, const uint8_t *data) { + while (size-- > 0) { + TWDR = *data++; + TWCR = (1 << TWINT) | (1 << TWEN); // send data byte + while (!(TWCR & (1 << TWINT))) {}; // wait until last action done + uint8_t sr = TWSR & 0xf8; + if (sr != 0x28) { + return 0x0500 | sr; + } + } + return 0; +} + +uint16_t I2c::writeByte (uint8_t data) { + return writeData(1, &data); +} + +uint16_t I2c::readData (uint8_t size, uint8_t *data) { + while (size-- > 0) { + if (size > 0) { + TWCR = (1 << TWEA) | (1 << TWINT) | (1 << TWEN); // read data byte with ACK enabled + } else { + TWCR = (1 << TWINT) | (1 << TWEN); // read data byte with ACK disabled + } + while (!(TWCR & (1 << TWINT))) {}; // wait until last action done + uint8_t sr = TWSR & 0xf8; + if ((size > 0 && sr != 0x50) || (size == 0 && sr != 0x58)) { + return 0x0600 | sr; + } + *data++ = TWDR; + } + return 0; +} + +int32_t I2c::compensateBm280T (int32_t adcT) { + int32_t var1, var2, t; + var1 = ((((adcT >> 3) - ((int32_t)bm280.digT[0] << 1))) * ((int32_t)bm280.digT[1])) >> 11; + var2 = (((((adcT >> 4) - ((int32_t)bm280.digT[0])) * ((adcT >> 4) - ((int32_t)bm280.digT[0]))) >> 12) * ((int32_t)bm280.digT[2])) >> 14; + bm280.tFine = var1 + var2; + t = (bm280.tFine * 5 + 128) >> 8; + return t; +} \ No newline at end of file diff --git a/software/test_2024-07-23/src/units/i2c.hpp b/software/test_2024-07-23/src/units/i2c.hpp new file mode 100644 index 0000000..96a3f23 --- /dev/null +++ b/software/test_2024-07-23/src/units/i2c.hpp @@ -0,0 +1,37 @@ +#ifndef I2C_HPP +#define I2C_HPP + +#include +#include "../main.hpp" + +typedef enum I2cMode { SparkFunEnvCombo, Master, Slave } I2cMode; + +typedef struct { + int32_t tFine; + uint16_t digT[3]; +} I2cBm280; + +class I2c : public TestUnit { + private: + I2cMode mode; + I2cBm280 bm280; + + public: + bool enabled; + + public: + I2c (I2cMode mode) { enabled = false; this->mode = mode; } + virtual void cleanup (); + virtual int8_t run (uint8_t subtest); + virtual const char *getName (); + void handleTwiIrq (); + uint16_t startRead (uint8_t address); + uint16_t startWrite (uint8_t address); + void stop (); + uint16_t writeByte (uint8_t data); + uint16_t writeData (uint8_t size, const uint8_t *data); + uint16_t readData (uint8_t size, uint8_t *data); + int32_t compensateBm280T (int32_t adcT); +}; + +#endif \ No newline at end of file