Remote_Wifi_Switch/main/i2c_sensors.c
2025-02-21 15:26:53 +05:30

1730 lines
46 KiB
C
Raw Blame History

This file contains ambiguous Unicode characters

This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

/*
* i2c_sensors.c
*
* Created on: Jan 23, 2023
* Author: Sword
*/
#include "driver/i2c.h"
#include <stdio.h>
#include <math.h>
#include "esp_log.h"
#include "driver/gpio.h"
#include "i2c_sensors.h"
#include "data_processing.h"
#include "ulp_main.h"
#include "port.h"
static const char *TAG = "I2C";
#define LOG_LOCAL_LEVEL ESP_LOG_INFO
#define I2C_MASTER_SCL_IO GPIO_NUM_2 /*!< GPIO number used for I2C master clock */
#define I2C_MASTER_SDA_IO GPIO_NUM_3 /*!< GPIO number used for I2C master data */
#define I2C_MASTER_NUM 0 /*!< I2C master i2c port number, the number of i2c peripheral interfaces available will depend on the chip */
#define I2C_MASTER_FREQ_HZ 100000 /*!< I2C master clock frequency */
#define I2C_MASTER_TX_BUF_DISABLE 0 /*!< I2C master doesn't need buffer */
#define I2C_MASTER_RX_BUF_DISABLE 0 /*!< I2C master doesn't need buffer */
#define I2C_MASTER_TIMEOUT_MS (1000/ portTICK_PERIOD_MS)
/*buffers to store incoming data/values from different sensors*/
//union byteAccessibleUint16 rawHumidity;
//union byteAccessibleUint16 rawTemperature;
//union byteAccessibleInt16 rawThermocoupleTemperature;
typedef struct
{
union
{
uint8_t state:2;
uint8_t res_mod:1;
uint8_t reserv:1;
uint8_t i2c_wdt:1;
uint8_t reser2:2;
uint8_t otp_busy:1;
uint8_t data;
};
}status_t;
//Sensor Data
/*RTC_DATA_ATTR static float temperature;
RTC_DATA_ATTR static float humidity;
RTC_DATA_ATTR static float thermocoupleTemp;*/
static float temperature;
static float humidity;
static float thermocoupleTemp;
RTC_DATA_ATTR uint32_t light_data;
RTC_DATA_ATTR uint32_t prev_light_data;
float light_full_scale;
//Sensor previous Data
/*RTC_DATA_ATTR static float prev_temperature;
RTC_DATA_ATTR static float prev_humidity;
RTC_DATA_ATTR static float prev_thermocoupleTemp;*/
static uint16_t ens210_devid;
static uint8_t mc3419_chipId;
static uint8_t mcp9600_idRevision;
static uint16_t accel_x;
static uint16_t accel_y;
static uint16_t accel_z;
static uint8_t i2cBuffer[6];
esp_err_t i2c_get_accel_reg_byte(uint8_t *reg, uint8_t *byte);
void i2c_master_init(void)
{
/*Set the port number of i2c-peripheral on chip*/
i2c_port_t i2c_master_port = I2C_MASTER_NUM;
/*setting the i2c peripheral to act as an i2c-master*/
i2c_config_t conf = {
.mode = I2C_MODE_MASTER,
.sda_io_num = I2C_MASTER_SDA_IO,
.scl_io_num = I2C_MASTER_SCL_IO,
.sda_pullup_en = GPIO_PULLUP_DISABLE,
.scl_pullup_en = GPIO_PULLUP_DISABLE,
.master.clk_speed = I2C_MASTER_FREQ_HZ,
};
/*Configuring the i2c with the previous settings*/
ESP_ERROR_CHECK(i2c_param_config(i2c_master_port, &conf));
/*Install the configured i2c driver*/
ESP_ERROR_CHECK(i2c_driver_install(i2c_master_port, conf.mode, I2C_MASTER_RX_BUF_DISABLE, I2C_MASTER_TX_BUF_DISABLE, 0));
}
/*Sensors initialization functions*/
/**********************************/
bool i2c_initialize_temp_humidity_sensor(void)
{
bool flag = false;
if(ESP_OK == i2c_ens210_set_active_mode())
{
flag = true;
ESP_LOGI(TAG, "ENS210 Setting Active Mode");
}
if(ESP_OK == i2c_ens210_fetch_dev_id())
{
ESP_LOGI(TAG, "ENS210 part ID: %02X", get_ens210_devId());
}
if(ESP_OK != i2c_start_temp_humid())
{
flag = false;
}
return flag;
}
bool i2c_initialize_accel_sensor(void)
{
bool flag = flag;
if(ESP_OK == i2c_get_mc3419_state())
{
flag = true;
/* These settings should be set in standby mode (before switch to wakeup mode)*/
/* ACCELEROMETER threshold should be set at each accelerometer initialization */
/* 1- switch to STANDBY mode*/
if(ESP_OK == i2c_set_mc3419_mode(MC3419_STANDBY_MODE))
{
/* 2- Set Initial motion threshold*/
if(ESP_OK == i2c_set_mc3419_motionThreshold(data_get_motion_threshold()))
{
/* 3- Enable interrupt flag INT1 for accelerometer*/
i2c_enable_mc3419_motion_int(true);
/* 4- Clear all pending INT flags*/
i2c_clear_mc3419_int_flag();
/*LOG*/
ESP_LOGI(TAG,"The new motion_detection threshold %d has been set",data_get_motion_threshold());
}
}
if(ESP_OK == i2c_set_mc3419_mode(MC3419_WAKE_MODE))
{
if(ESP_OK == i2c_fetch_mc3419_chipId())
{
ESP_LOGI(TAG, "MC3419 Chip Id: %02X", get_mc3419_chipId());
i2c_get_mc3419_state();
}
else
{
ESP_LOGI(TAG, "Failed to get MC3419 chipid");
flag = false;
}
}
else
{
ESP_LOGI(TAG, "Failed to set MC3419 to wake mode");
flag = false;
}
}
else
{
ESP_LOGI(TAG, "Failed to get MC3419 state");
}
return flag;
}
/*ENS210-Sensor functions*/
/**********************************/
esp_err_t i2c_start_temp_humid(void)
{
esp_err_t ret = ESP_FAIL;
i2cBuffer[0] = ENS210_SENS_RUN;
i2cBuffer[1] = 3;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, ENS210_ADDR, i2cBuffer, 2, 1000 / portTICK_PERIOD_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send sensor run request to ENS210.");
return ret;
}
i2cBuffer[0] = ENS210_SENS_START;
i2cBuffer[1] = 3;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, ENS210_ADDR, i2cBuffer, 2, 131 / portTICK_PERIOD_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send sensor start request to ENS210.");
}
return ret;
}
esp_err_t i2c_stop_temp_humid(void)
{
esp_err_t ret = ESP_FAIL;
i2cBuffer[0] = ENS210_SENS_STOP;
i2cBuffer[1] = 3;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, ENS210_ADDR, i2cBuffer, 2, 1000 / portTICK_PERIOD_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send sensor stop request to ENS210.");
return ret;
}
return ret;
}
esp_err_t i2c_fetch_temp(void)
{
uint16_t temp = 0;
uint16_t hum = 0;
float tempC = 0;
// Read temperature and humidity
i2cBuffer[0] = ENS210_T_VAL;
esp_err_t ret = ESP_FAIL;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, ENS210_ADDR, &i2cBuffer[0], 1, (I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to send T_VAL command to ENS210 sensor.");
return ret;
}
ret = i2c_master_read_from_device(I2C_MASTER_NUM, ENS210_ADDR, i2cBuffer, 6, (I2C_MASTER_TIMEOUT_MS));
if(ret == ESP_OK)
{
//ESP_LOGI(TAG, "Reading temperature and humidity from ENS210 sensor");
}
else
{
ESP_LOGI(TAG, "Failed to read from ENS210 sensor");
return ret;
}
if(i2cBuffer[2] & 0x01)
{
temp = i2cBuffer[0] | (i2cBuffer[1] << 8);
tempC = temp/64.0;
tempC -= 273.15;
ulp_ulp_prev_temperature = ulp_ulp_temperature;
ulp_ulp_temperature = tempC;
ulp_ens_temp_raw = temp;
temperature = tempC;
}
else
{
ESP_LOGI(TAG, "Invalid temperature data");
}
if(i2cBuffer[5] & 0x01)
{
hum = i2cBuffer[3] | (i2cBuffer[4] << 8);
ulp_ulp_prev_humidity = ulp_ulp_humidity;
ulp_ulp_humidity = hum/512.0;
humidity = hum/512.0;
ulp_humidity_raw = hum;
}
else
{
ESP_LOGI(TAG, "Invalid humidity data");
}
return ret;
}
float get_temperature_data(void)
{
return temperature;
}
float get_prev_temperature_data(void)
{
return ulp_ulp_prev_temperature;
}
float get_humidity_data(void)
{
return humidity;
}
float get_prev_humidity_data(void)
{
return ulp_ulp_prev_humidity;
}
esp_err_t i2c_ens210_fetch_dev_id(void)
{
i2cBuffer[0] = ENS210_PART_ID;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, ENS210_ADDR, i2cBuffer, 1, 1000 / portTICK_PERIOD_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send part ID request to ENS210.");
return ret;
}
vTaskDelay(100 / portTICK_PERIOD_MS);
ret = i2c_master_read_from_device(I2C_MASTER_NUM, ENS210_ADDR, i2cBuffer, 2, (I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to receive any part ID response from ENS210.");
}
ens210_devid = i2cBuffer[1] | (i2cBuffer[0] << 8);
return ret;
}
uint16_t get_ens210_devId(void)
{
return ens210_devid;
}
esp_err_t i2c_ens210_set_active_mode(void)
{
i2cBuffer[0] = ENS210_SYS_CTRL;
i2cBuffer[1] = 0;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, ENS210_ADDR, i2cBuffer, 2, I2C_MASTER_TIMEOUT_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send active mode write request to ENS210.");
return ret;
}
vTaskDelay(1000 / portTICK_PERIOD_MS);
i2cBuffer[0] = ENS210_SYS_STAT;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, ENS210_ADDR, i2cBuffer, 1, I2C_MASTER_TIMEOUT_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send sys stat read request to ENS210.");
return ret;
}
ret = i2c_master_read_from_device(I2C_MASTER_NUM, ENS210_ADDR, i2cBuffer, 1, I2C_MASTER_TIMEOUT_MS);
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to receive sys stat response from ENS210.");
}
else
{
ESP_LOGI(TAG, "ENS210 sys stat: %d", i2cBuffer[0]);
}
return ret;
}
/*MC3419-Sensor functions*/
/**********************************/
esp_err_t i2c_fetch_mc3419_chipId(void)
{
i2cBuffer[0] = CHIP_IDENTIFICATION_REGISTER;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, i2cBuffer, 1, I2C_MASTER_TIMEOUT_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send chip id request to MC3419.");
return ret;
}
ret = i2c_master_read_from_device(I2C_MASTER_NUM, MC3419_ADDR, i2cBuffer, 1, I2C_MASTER_TIMEOUT_MS);
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to get chip id response from MC3419.");
}
else
{
mc3419_chipId = i2cBuffer[0];
}
return ret;
}
uint16_t get_mc3419_chipId(void)
{
return mc3419_chipId;
}
esp_err_t i2c_get_accel_reg_byte(uint8_t *reg, uint8_t *byte)
{
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, reg, 1, I2C_MASTER_TIMEOUT_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send read reg request to MC3419.");
return ret;
}
ret = i2c_master_read_from_device(I2C_MASTER_NUM, MC3419_ADDR, byte, 1, I2C_MASTER_TIMEOUT_MS);
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to get read reg response from MC3419.");
}
return ret;
}
esp_err_t i2c_set_mc3419_mode(uint8_t mode)
{
status_t s;
i2cBuffer[0] = MODE_REGISTER;
i2c_get_accel_reg_byte(i2cBuffer, (uint8_t *)&s);
s.state = 1;
s.res_mod = mode;
i2cBuffer[1] = s.data;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, i2cBuffer, 2, I2C_MASTER_TIMEOUT_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send mode request to MC3419.");
}
return ret;
}
esp_err_t i2c_get_mc3419_state(void)
{
i2cBuffer[0] = DEVICE_STATUS_REGISTER;
status_t status;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, i2cBuffer, 1, I2C_MASTER_TIMEOUT_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send status reg request to MC3419.");
return ret;
}
ret = i2c_master_read_from_device(I2C_MASTER_NUM, MC3419_ADDR, (uint8_t *)&status, 1, I2C_MASTER_TIMEOUT_MS);
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to get status reg response from MC3419.");
}
else
{
ESP_LOGI(TAG, "Device Status: STATE: %d RES_MODE: %d I2C_WDT: %d OTP_BUSY: %d", status.state, status.res_mod, status.i2c_wdt, status.otp_busy);
}
return ret;
}
esp_err_t i2c_fetch_accel_pos(void)
{
i2cBuffer[0] = XOUT_ACCELEROMETER_DATA_LSB_REGISTER;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, i2cBuffer, 1, I2C_MASTER_TIMEOUT_MS);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send XYZ request to MC3419.");
return ret;
}
ret = i2c_master_read_from_device(I2C_MASTER_NUM, MC3419_ADDR, i2cBuffer, 6, I2C_MASTER_TIMEOUT_MS);
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to get XYZ response from MC3419.");
}
else
{
accel_x = i2cBuffer[0] | (i2cBuffer[1] << 8);
accel_y = i2cBuffer[2] | (i2cBuffer[3] << 8);
accel_z = i2cBuffer[4] | (i2cBuffer[5] << 8);
}
return ret;
}
esp_err_t i2c_clear_mc3419_int_flag(void)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/* 3- Setting up the register address and its value */
i2cBuffer[0] = INTERRUPT_STATUS_REGISTER;
i2cBuffer[1] = 0x00; // Clear all pending interrupt flags.
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to clear all pending interrupt flags of MC3419.");
return ret;
}
//Log the following message for indication
ESP_LOGI(TAG,"all pending interrupt flags of MC3419 have been cleared successfully");
vTaskDelay(1000 / portTICK_PERIOD_MS);
return ret;
}
esp_err_t i2c_get_mc3419_int_flags(uint8_t *flags)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/* 2- Set the register address and the receiving buffer*/
i2cBuffer[0] = INTERRUPT_STATUS_REGISTER;
/* 3- read one byte from the INTERRUPT_STATUS_REGISTER*/
esp_err_t ret = i2c_get_accel_reg_byte(&i2cBuffer[0],&i2cBuffer[1]);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to read one from the INTERRUPT_STATUS_REGISTER of MC3419.");
return ret;
}
//Log the following message for indication
ESP_LOGI(TAG,"Reading one byte from the INTERRUPT_STATUS_REGISTER of MC3419 successfully");
/* 4- Storing the received byte in the corresponding pointer*/
*flags = i2cBuffer[1];
vTaskDelay(1000 / portTICK_PERIOD_MS);
return ret;
}
esp_err_t i2c_enable_mc3419_motion_int(bool enableFlag)
{
// Return true if ok, return false if invalid data or error.
uint8_t tempByte;
uint8_t tempMode;
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/* 2- Set the register address (MODE_REGISTER)*/
i2cBuffer[0] = MODE_REGISTER;
/* 3- Read current mode, so we can return to it after configuring the device*/
esp_err_t ret = i2c_get_accel_reg_byte(&i2cBuffer[0],&tempMode);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to read the current mode of MC3419.");
return ret;
}
// Keep only the mode bits.
tempMode &= 0x03;
/* 4- Switch to STANDBY mode if necessary*/
if(MC3419_STANDBY_MODE != tempMode)
{
ret = i2c_set_mc3419_mode(MC3419_STANDBY_MODE);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to switch to STANDBY-MODE for MC3419.");
return ret; // I2C error.
}
}
/* 5- Set the register address (INTERRUPT_ENABLE_REGISTER)*/
i2cBuffer[0] = INTERRUPT_ENABLE_REGISTER;
/* 6- Read and update AnyMotion interrupt enable bit.*/
ret = i2c_get_accel_reg_byte(&i2cBuffer[0],&tempByte);
ESP_LOGI(TAG, "MC3419 interrupt register: 0x%X", tempByte);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to read interrupt enable bit of MC3419.");
return ret;
}
if(enableFlag)
tempByte |= 0x04; // Enable AnyMotion interrupt.
else
tempByte &= ~0x04; // Disable AnyMotion interrupt.
/* 7- Setting up the register address and its value */
i2cBuffer[0] = INTERRUPT_ENABLE_REGISTER;
i2cBuffer[1] = tempByte;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to update the AnyMotion interrupt enable bit of MC3419.");
return ret;
}
vTaskDelay(100 / portTICK_PERIOD_MS);
i2cBuffer[0] = INTERRUPT_ENABLE_REGISTER;
/* Read INTERRUPT_ENABLE_REGISTER to confirm if the interrupt flags are set.*/
ret = i2c_get_accel_reg_byte(&i2cBuffer[0],&tempByte);
ESP_LOGI(TAG, "MC3419 INTERRUPT_ENABLE_REGISTER: 0x%X", tempByte);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to read INTERRUPT_ENABLE_REGISTER of MC3419.");
return ret;
}
/* 4- Restore original mode.*/
if(MC3419_STANDBY_MODE != tempMode)
{
ret = i2c_set_mc3419_mode(tempMode);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to restore the original mode of MC3419.");
return ret; // I2C error.
}
}
// From MC3419 data sheet
if(MC3419_WAKE_MODE == tempMode)
vTaskDelay(1000 / portTICK_PERIOD_MS);
// No error. Data valid.
return ret;
}
esp_err_t i2c_set_mc3419_motionThreshold(uint16_t threshold)
{
// Return true if ok, return false if invalid data or error.
uint8_t tempByte;
uint8_t tempMode;
/* Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
// Read current mode, so we can return to it after configuring the device.
i2cBuffer[0] = MODE_REGISTER;
/* Read and update AnyMotion interrupt enable bit.*/
esp_err_t ret = i2c_get_accel_reg_byte(&i2cBuffer[0],&tempMode);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to read the mode of MC3419.");
return ret;
}
// Keep only the mode bits.
tempMode &= 0x03;
/* Switch to STANDBY mode if necessary*/
if(MC3419_STANDBY_MODE != tempMode)
{
ret = i2c_set_mc3419_mode(MC3419_STANDBY_MODE);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to switch to STANDBY-MODE for MC3419.");
return ret; // I2C error.
}
}
// Set sample rate.
i2cBuffer[0] = SAMPLE_RATE_REGISTER;
i2cBuffer[1] = 0x08; // Sample rates are different for the MC3419 and MC3419-P chips.
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to set the new sample rate of MC3419.");
return ret;
}
// Disable decimation.
i2cBuffer[0] = FIFO_CONTROL_2_AND_SAMPLE_RATE_2_REGISTER;
i2cBuffer[1] = 0x00;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to disable decimation of MC3419.");
return ret;
}
// Configure AnyMotion feature.
i2cBuffer[0] = ANY_MOTION_THRESHOLD_MSB_REGISTER;
i2cBuffer[1] = (uint8_t)((threshold >> 8) & 0x007F); // Bit 7 is reserved.
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to configure AnyMotion feature of MC3419.");
return ret;
}
i2cBuffer[0] = ANY_MOTION_THRESHOLD_LSB_REGISTER;
i2cBuffer[1] = (uint8_t)(threshold & 0x00FF);
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to set the value LSB threshold of MC3419.");
return ret;
}
i2cBuffer[0] = ANY_MOTION_DEBOUNCE_REGISTER;
i2cBuffer[1] = 0x00;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to set the value of DEBOUNCE_REGISTER of MC3419.");
return ret;
}
// Enable AnyMotion feature.
i2cBuffer[0] = MOTION_CONTROL_REGISTER;
ret = i2c_get_accel_reg_byte(&i2cBuffer[0],&tempByte);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to enable AnyMotion feature of MC3419.");
return ret;
}
// Motion block in reset?
if(0x80 == (tempByte & 0x80))
{
ESP_LOGI(TAG, "Warning: resetting accelerometer motion control block.");
// Reset Motion block.
i2cBuffer[0] = MOTION_CONTROL_REGISTER;
i2cBuffer[1] = 0x80;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to Reset Motion block of MC3419.");
return ret;
}
}
// Enable AnyMotion feature.
i2cBuffer[0] = MOTION_CONTROL_REGISTER;
i2cBuffer[1] = 0x04;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to Enable AnyMotion feature again of MC3419.");
return ret;
}
// Configure interrupt hardware pins.
i2cBuffer[0] = GPIO_CONTROL_REGISTER;
i2cBuffer[1] = 0xCC; // Configure both interrupt pins as push-pull, active high.
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MC3419_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to configure interrupt hardware pins of MC3419.");
return ret;
}
/* Restore original mode.*/
if(MC3419_STANDBY_MODE != tempMode)
{
ret = i2c_set_mc3419_mode(tempMode);
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to restore the original mode of MC3419.");
return ret; // I2C error.
}
}
// From MC3419 data sheet
if(MC3419_WAKE_MODE == tempMode)
vTaskDelay(1000 / portTICK_PERIOD_MS);
// No error. Data valid.
return ret;
}
uint16_t get_accel_x(void)
{
return accel_x;
}
uint16_t get_accel_y(void)
{
return accel_y;
}
uint16_t get_accel_z(void)
{
return accel_z;
}
/*MCP9600-Sensor functions*/
/**********************************/
bool i2c_initialize_thermocouple_sensor(void)
{
bool flag = false;
if(ESP_OK == i2c_mcp9600_set_type(THERMOCOUPLE_TYPE_K))
{
flag = true;
}
if(ESP_OK == i2c_mcp9600_fetch_dev_id())
{
ESP_LOGI(TAG, "MCP9600 part ID & Revision: %02X", get_mcp9600_devId());
}
if(ESP_OK != i2c_start_thermocoupleConversion())
{
flag = false;
}
return flag;
}
esp_err_t i2c_mcp9600_set_burst_mode(void)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/*A Burst Mode of one sample will execute, then device will go into Shutdown mode*/
/* we have to clear the flags that are related to the previous conversion
* The configuration register is as following
*
* Bit7 | Bit6 | Bit5 | Bit4 | Bit3 | Bit2 | Bit1 | Bit0
* ------------------------------------------------------------------------------
* Cold-Junc| ADC Measurement | Burst Mode Temperature | Shutdown
* resol. | Resolution | Samples | Modes
*
*cold-Junction/Ambient Sensor Resolution:
* 0 = 0.0625°C
* 1 = 0.25°C
*bit 6-5 ADC Measurement Resolution: ADC Resolution bits (see Table 5-3):
* 00 =18-bit Resolution
* 01 =16-bit Resolution
* 10 =14-bit Resolution
* 11 =12-bit Resolution
*bit 4-2 Burst Mode Temperature Samples: Number of Temperature Samples bits
* 000 = 1 sample
* 001 = 2 samples
* 010 = 4 samples
* 011 = 8 samples
* 100 = 16 samples
* 101 = 32 samples
* 110 = 64 samples
* 111 = 128 samples
*bit 1-0 Shutdown Modes: Shutdown Mode bits
* 00 = Normal operation
* 01 = Shutdown mode
* 10 = Burst mode
* 11 = Unimplemented: this setting has no effect
*
* */
/* 3- Setting up the required sensor configurations */
i2cBuffer[0] = MCP9600_DEVICE_CONFIG_REG;
i2cBuffer[1] = 0xA2; // 0.25C cold junction resolution, 16-bit ADC resolution, 1 sample when in Burst mode, Burst mode.
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to Burst-mode and its configuration to MCP9600.");
return ret;
}
//Log the following message for indication
//ESP_LOGI(TAG,"Burst-mode and its configuration have been set to MCP9600\r\n");
vTaskDelay(1000 / portTICK_PERIOD_MS);
return ret;
}
esp_err_t i2c_mcp9600_fetch_dev_id(void)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/* 2- LOOK FOR A MCP9600 SENSOR (THERMOCOOUPLE) */
i2cBuffer[0] = MCP9600_DEVICE_ID_REVISION;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 1, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send part ID request to MCP9600.");
return ret;
}
/* Delay for some time Required by MCP9600 data sheet */
vTaskDelay(100/portTICK_PERIOD_MS);
/* Note that the MCP9600 chip reads out big endian.
* Chip ID must be 0x40 and revision must be greater than 0x13.
* Older chips have a bad bug in them.
* */
ret = i2c_master_read_from_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 2,(I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to receive any part ID response from MCP9600.");
}
/*Store the device ID in its corresponding buffer*/
mcp9600_idRevision = i2cBuffer[1] | (i2cBuffer[0] << 8);
return ret;
}
uint16_t get_mcp9600_devId(void)
{
return mcp9600_idRevision;
}
esp_err_t i2c_start_thermocoupleConversion(void)
{
esp_err_t ret = ESP_FAIL;
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/* we have to clear the flags that are related to the previous conversion
* (Clear Burst Complete and Th Update bits)
* The status register is as following
*
* Bit7 | Bit6 | Bit5 | Bit4 | Bit3 | Bit2 | Bit1 | Bit0
* ------------------------------------------------------------------------------
* Burst |TH Update| Short | Input | Alert 4 | Alert 3 | Alert 2 | Alert 1
* Complete | | Circuit | Range | Status | Status | Status | Status
*
* Burst Complete: Burst Mode Conversions Status Flag bit
* 1 = TΔ register Burst mode conversions complete
* 0 = Writing 0 has no effect
* Once Burst mode is enabled, this bit is normally set after the first burst is complete. User can clear it and
* poll the bit periodically until the next burst of temperature conversions is complete
* TH Update: Temperature Update Flag bit
* 1 = Temperature conversion complete
* 0 = Writing 0 has no effect
* This bit is normally set. User can clear it and poll the bit until the next temperature conversion is complete
*
* */
/* 2- Clear both the Burst Complete flag and ThUpdate flag to start a new conversion */
i2cBuffer[0] = MCP9600_STATUS_REG;
i2cBuffer[1] = 0xC0;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to reset flags of MCP9600 that are related to previous conversion");
return ret;
}
ret = i2c_mcp9600_set_burst_mode();
if(ESP_OK != ret)
{
return ret;
}
//Log the following message for indication
//ESP_LOGI(TAG,"Setting up for new conversion process\r\n");
return ret;
}
esp_err_t i2c_fetch_thermocoupleTemp(void)
{
esp_err_t ret = ESP_FAIL;
uint16_t temp;
uint8_t counter = 0;
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/*Clear flags*/
i2c_start_thermocoupleConversion();
/* 2- Wait until the previously-started conversions get completed */
do
{
/*Send the request to read from the MCP9600 status register*/
i2cBuffer[0] = MCP9600_STATUS_REG;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 1, (I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to send status request to MCP9600 sensor.");
return ret;
}
/*Read the response from the MCP9600*/
ret = i2c_master_read_from_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 1, (I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to receive any status response from MCP9600 sensor.");
return ret;
}
/*Check the time-out*/
counter++;
if (3 < counter){ // Wait for at least one complete temperature conversion to occur since waking up. This can take up to 332 milliseconds, including the temperature calculation time.
ESP_LOGI(TAG, "Timeout for getting data from MCP9600 sensor.");
return(ESP_FAIL); // Timeout.
}
/* Delay for some time Required by MCP9600 data sheet */
vTaskDelay(111/portTICK_PERIOD_MS);
} while (!(i2cBuffer[0] & MCP9600_TH_UPDATE_BIT));
/* If Input Range Bit (temperature valid flag) is set then
* there is a sensor error, such as an open or shorted thermocouple, etc*/
/* 3- Check to ensure that input-range-bit didn't set*/
if(!(i2cBuffer[0] & MCP9600_INPUT_RANGE_BIT))
{
/* 4- Read the conversion result */
/*Send the request to MCP9600 to read the temperature*/
i2cBuffer[0] = MCP9600_HOT_JUNCTION_REG;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0],1, (I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to send temperature request to MCP9600 sensor.");
return ret;
}
/*Read the response from MCP9600*/
ret = i2c_master_read_from_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to receive any temperature response from MCP9600 sensor.");
return ret;
}
/*Check if the temperature is equal or greater than zero*/
/*temp = i2cBuffer[1] | (i2cBuffer[0] << 8);
if(temp >= 0)
thermocoupleTemp = (i2cBuffer[1]*16) + (i2cBuffer[0] /16);
else
thermocoupleTemp = (i2cBuffer[1]*16) + (i2cBuffer[0] /16) - 4096;*/
temp = i2cBuffer[1] | (i2cBuffer[0] << 8);
ulp_ulp_prev_thermocoupleTemp = ulp_ulp_thermocoupleTemp;
ulp_ulp_thermocoupleTemp = temp;
ulp_ulp_thermocoupleTemp /= 16;
thermocoupleTemp = temp/16.0;
if(temp & 0x8000) // Adjust for sign bit
{
ulp_ulp_thermocoupleTemp -= 4096;
thermocoupleTemp -= 4096;
}
ulp_thermo_temp_raw = ulp_ulp_thermocoupleTemp;
}
/* Delay for some time Required by MCP9600 data sheet */
vTaskDelay(100/portTICK_PERIOD_MS);
return ret;
}
float get_thermocouple_data(void)
{
return thermocoupleTemp;
}
float get_prev_thermocouple_data(void)
{
return ulp_ulp_prev_thermocoupleTemp;
}
esp_err_t i2c_mcp9600_set_alert_config(alertNum_t alertNum)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/* Bit7 | Bit6 | Bit5 | Bit4 | Bit3 | Bit2 | Bit1 | Bit0
* -----------------------------------------------------------------------------------
* Interrupt| --------------- | Monitor | Rise or | ActiveHigh | Comp/Int | Alert
* clear | | TH/TC | Fall | ActiveLow | | Enable
*bit 7 Interrupt Clear: Interrupt Clear bit
* 1 = Clears Interrupt flag (forced 0 by device)
* 0 = Normal state or cleared state
*bit 6-5 Unimplemented: Read as 0
*bit 4 Monitor TH or TC: Temperature Maintain/Detect bit
* 1 = Alert monitor for TC cold-junction sensor
* 0 = Alert monitor for TH thermocouple temperature
*bit 3 Rise/Fall: Alert Temperature Direction bit
* 1 = Alert limit for falling or cooling temperatures
* 0 = Alert limit for rising or heating temperatures
*bit 2 Active-High/Low: Alert State bit
* 1 = Active-high
* 0 = Active-low
*bit 1 Comp./Int.: Alert Mode bit
* 1 = Interrupt mode: Interrupt clears bit (bit 7) must be set to deassert the alert output
* 0 = Comparator mode
*bit 0 Alert Enable: Alert Output Enable bit
* 1 = Alert output is enabled
* 0 = Alert output is disabled
*/
/* 3- Determine which Alert to set */
switch(alertNum)
{
case 1: i2cBuffer[0] = MCP9600_ALERT1_CONFIG_REG; break;
case 2: i2cBuffer[0] = MCP9600_ALERT2_CONFIG_REG; break;
case 3: i2cBuffer[0] = MCP9600_ALERT3_CONFIG_REG; break;
case 4: i2cBuffer[0] = MCP9600_ALERT4_CONFIG_REG; break;
default: i2cBuffer[0] = 0; break;
}
i2cBuffer[1] = 0b10000111;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to set Alert%d configurations MCP9600.",alertNum);
return ret;
}
//Log the following message for indication
ESP_LOGI(TAG,"Set Alert%d confiurations",alertNum);
vTaskDelay(1000 / portTICK_PERIOD_MS);
return ret;
}
esp_err_t i2c_mcp9600_set_alert_limit(alertNum_t alertNum, float alertLimit)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[3];
uint16_t limitValue = 0;
uint16_t temp;
/* 2- Determine which Alert to set */
switch(alertNum)
{
case 1: i2cBuffer[0] = MCP9600_ALERT1_LIMIT_REG; break;
case 2: i2cBuffer[0] = MCP9600_ALERT2_LIMIT_REG; break;
case 3: i2cBuffer[0] = MCP9600_ALERT3_LIMIT_REG; break;
case 4: i2cBuffer[0] = MCP9600_ALERT4_LIMIT_REG; break;
default: i2cBuffer[0] = 0; break;
}
/*Check if the alert limit is positive or negative*/
if(alertLimit < 0)
{
limitValue |= 0b0000100000000000;
alertLimit *= -1;
}
/*init the value for the buffer*/
if(alertLimit > 2047)
limitValue = 2047;
else
{
temp = (uint16_t)(alertLimit);
temp &= 0b0000011111111111;
limitValue = temp << 4;
}
/*Estimate the fraction*/
temp = (((uint16_t)(alertLimit*100)) % 100);
if(temp>=25 && temp<50)
limitValue &= 4;
else if(temp>=50 && temp<75)
limitValue &= 8;
else
limitValue &= 12;
/* 3- Put the limit in the i2c buffer*/
i2cBuffer[1] = limitValue>>8; //high byte firstly
i2cBuffer[2] = limitValue; //low byte secondly
/*Send the limit*/
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 3, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to set Alert%d limit MCP9600.",alertNum);
return ret;
}
//Log the following message for indication
ESP_LOGI(TAG,"Set Alert%d limit",alertNum);
vTaskDelay(1000 / portTICK_PERIOD_MS);
return ret;
}
esp_err_t i2c_mcp9600_set_alert_hyst(alertNum_t alertNum, float alertHyst)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/* 2- Determine which Alert to set */
switch(alertNum)
{
case 1: i2cBuffer[0] = MCP9600_ALERT1_HYST_REG; break;
case 2: i2cBuffer[0] = MCP9600_ALERT2_HYST_REG; break;
case 3: i2cBuffer[0] = MCP9600_ALERT3_HYST_REG; break;
case 4: i2cBuffer[0] = MCP9600_ALERT4_HYST_REG; break;
default: i2cBuffer[0] = 0; break;
}
/* 3- constrain alertHyst*/
if(alertHyst > 255)
alertHyst = 255;
else if(alertHyst < 0)
alertHyst = 0;
/*Put the Hyst in i2c buffer*/
i2cBuffer[1] = (uint16_t)(alertHyst);
/*Send the limit*/
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to set Alert%d Hysteresis MCP9600.",alertNum);
return ret;
}
//Log the following message for indication
ESP_LOGI(TAG,"Set Alert%d Hysteresis",alertNum);
vTaskDelay(1000 / portTICK_PERIOD_MS);
return ret;
}
esp_err_t i2c_mcp9600_set_sleep(void)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/* 2- Start new conversion */
i2cBuffer[0] = MCP9600_DEVICE_CONFIG_REG;
i2cBuffer[1] = 0xA1; // 0.25C cold junction resolution, 16-bit ADC resolution, 1 sample when in Burst mode, Shutdown mode.
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to set Shutdown-mode and its configuration to MCP9600.");
return ret;
}
//Log the following message for indication
ESP_LOGI(TAG,"Shutdown-mode and its configuration have been set to MCP9600\r\n");
vTaskDelay(1000 / portTICK_PERIOD_MS);
return ret;
}
esp_err_t i2c_mcp9600_set_type(uint8_t thermocoupleType)
{
uint8_t tempThermocoupleType;
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
tempThermocoupleType = thermocoupleType;
tempThermocoupleType &= 0x70; // Keep thermocouple type. Set filter coefficient to "Filter off".
/* 2- Start new conversion */
i2cBuffer[0] = MCP9600_THERMOCOUPLE_CONFIG;
i2cBuffer[1] = tempThermocoupleType;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, MCP9600_ADDR, &i2cBuffer[0], 2, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to set thermocouple type of MCP9600.");
return ret;
}
//Log the following message for indication
ESP_LOGI(TAG,"Thermocouple type has been set successfully\r\n");
vTaskDelay(1000 / portTICK_PERIOD_MS);
return ret;
}
bool i2c_initialize_light_sensor(void)
{
/* Fetch manufacturer ID */
esp_err_t ret = i2c_opt3001_fetch_manufact_id();
if(ret != ESP_OK)
{
return false;
}
/* Fetch Device ID */
ret = i2c_opt3001_fetch_dev_id();
if(ret != ESP_OK)
{
return false;
}
/* Set the Conversion-Time */
ret = i2c_opt3001_set_conversion_time(CONVERSION_TIME_800Ms);
if(ret != ESP_OK)
{
return false;
}
/* Set the Converion-mode */
ret = i2c_opt3001_set_conversion_mode(SINGLE_SHOT_CONVERSION_MODE);
if(ret != ESP_OK)
{
return false;
}
/* Set the FULL_SCALE_LUX range */
ret = i2c_opt3001_set_full_lux_scale(FULL_SCALE_RANGE_LUX_655);
if(ret != ESP_OK)
{
return false;
}
return true;
}
esp_err_t i2c_opt3001_fetch_manufact_id(void)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/* 2- LOOK FOR A OPT3001 SENSOR (Light sensor) */
i2cBuffer[0] = MANUFACTURER_ID_REGISTER;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 1, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send manufacturer ID request to OPT3001.");
return ret;
}
/* Delay for some time Required */
vTaskDelay(100/portTICK_PERIOD_MS);
ret = i2c_master_read_from_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 2,(I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to receive any manufacturer ID response from OPT3001.");
}
else
{
ESP_LOGI(TAG, "The manufacturer ID response from OPT3001 is 0x%X%X",i2cBuffer[0],i2cBuffer[1]);
}
return ret;
}
esp_err_t i2c_opt3001_fetch_dev_id(void)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
/* 2- LOOK FOR A OPT3001 SENSOR (Light sensor) */
i2cBuffer[0] = DEVICE_ID_REGISTER;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 1, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send Device ID request to OPT3001.");
return ret;
}
/* Delay for some time Required */
vTaskDelay(100/portTICK_PERIOD_MS);
ret = i2c_master_read_from_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 2,(I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to receive any Device ID response from OPT3001.");
}
else
{
ESP_LOGI(TAG, "The Device ID response from OPT3001 is 0x%X%X",i2cBuffer[0],i2cBuffer[1]);
}
return ret;
}
uint16_t i2c_opt3001_fetch_configuration(void)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[2];
uint16_t config_reg;
/* 2- LOOK FOR A OPT3001 SENSOR (Light sensor) */
i2cBuffer[0] = CONFIGURATION_REGISTER;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 1, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send configuration request to OPT3001.");
return 0xFFFF;
}
/* Delay for some time Required */
vTaskDelay(100/portTICK_PERIOD_MS);
ret = i2c_master_read_from_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 2,(I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to receive any configuration response from OPT3001.");
return 0xFFFF;
}
config_reg = ((i2cBuffer[0]<<8)|i2cBuffer[1]);
return config_reg;
}
conversionFlagState_t i2c_opt3001_get_conv_ready_flag(void)
{
/* Read the configuration register*/
uint16_t config_reg = i2c_opt3001_fetch_configuration();
/* Check if MCU failed to read the configuration register */
if(0xFFFF == config_reg)
{
return FAILED_TO_READ_CONVERSION_READY_FLAG;
}
/* Extract and check the Conversion_ready_flag bit from the configuration register */
if((config_reg & 7))
return CONVERSION_READY_FLAG_IS_SET;
else
return CONVERSION_READY_FLAG_IS_NOT_SET_YET;
}
esp_err_t i2c_opt3001_fetch_light_data(void)
{
conversionFlagState_t conv_flag;
uint16_t result;
uint8_t exponent;
uint8_t counter = 0;
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[3];
/* Set the Conversion-Time */
esp_err_t ret = i2c_opt3001_set_conversion_time(CONVERSION_TIME_800Ms);
if(ret != ESP_OK)
{
return ret;
}
/* Set the Converion-mode */
ret = i2c_opt3001_set_conversion_mode(SINGLE_SHOT_CONVERSION_MODE);
if(ret != ESP_OK)
{
return ret;
}
/* delay for 0.6 second for conversion process */
vTaskDelay(850/portTICK_PERIOD_MS);
/* Read the conversion ready flag */
conv_flag = i2c_opt3001_get_conv_ready_flag();
/* Wait to complete the conversion process */
//while(CONVERSION_READY_FLAG_IS_SET != conv_flag)
//{
// if((conv_flag == FAILED_TO_READ_CONVERSION_READY_FLAG) || (counter == 20))
// {
// if(conv_flag == FAILED_TO_READ_CONVERSION_READY_FLAG)
// {
// ESP_LOGI(TAG,"Failed to read light data from the OPT3001 sensor (issue with analog conversion process)");
// }
// else if(counter == 20)
// {
// ESP_LOGI(TAG,"Failed to read light data from the OPT3001 sensor (timeout)");
// }
// return ESP_FAIL;
// }
//
// /* Wait for another 100ms*/
// vTaskDelay(100/portTICK_PERIOD_MS);
// counter++;
//
// /* Read the conversion ready flag */
// conv_flag = i2c_opt3001_get_conv_ready_flag();
//}
/* Send the address of the result register */
i2cBuffer[0] = RESULT_REGISTER;
ret = i2c_master_write_to_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 1, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send result request to OPT3001.");
return ESP_FAIL;
}
/* Delay for some time Required */
vTaskDelay(100/portTICK_PERIOD_MS);
/* Read the result register of the OPT3001 sensor */
ret = i2c_master_read_from_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 2,(I2C_MASTER_TIMEOUT_MS));
if(ESP_OK != ret)
{
ESP_LOGI(TAG, "Failed to receive any configuration response from OPT3001.");
return ESP_FAIL;
}
//ESP_LOGI(TAG,"-----> Result register is equal to = 0x%X%X",i2cBuffer[0],i2cBuffer[1]);
result = ((i2cBuffer[0]<<8) | i2cBuffer[1]);
result = result & 0x0FFF;
//exponent = (i2cBuffer[0] & 0xF0)>>4;
//light_data = 0.01 * pow(2,exponent) * result;
prev_light_data = light_data;
light_data = light_full_scale * result;
ulp_light_data_opt = light_data;
return ESP_OK;
}
uint32_t get_light_data(void)
{
return light_data;
}
uint32_t get_prev_light_data(void)
{
return prev_light_data;
}
esp_err_t i2c_opt3001_set_full_lux_scale(fullScaleRangeLux_t scale)
{
/*Note that the exponent field can be disabled (set to zero) by enabling the exponent mask (configuration register,
ME field = 1) and manually programming the full-scale range (configuration register, RN[3:0] < 1100b (0Ch)),
allowing for simpler operation in a manually-programmed, full-scale mode
*/
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[3];
uint8_t bit = 0;
/* Read the configuration register*/
uint16_t config_reg = i2c_opt3001_fetch_configuration();
/* Check if MCU failed to read the configuration register */
if(0xFFFF == config_reg)
{
return ESP_FAIL;
}
/* Set the Mask-exponent-field bit to 1 */
config_reg = config_reg | (1<<2);
/* Check the requested Full-scale */
for(uint8_t i = 0; i<4; i++)
{
bit = scale & (1<<i);
if(bit == 1)
config_reg = config_reg | (1<<(12+i));
else
config_reg = config_reg & (~(1<<(12+i)));
}
/* set the new values for the configuration register in the i2cbuffer array */
i2cBuffer[0] = CONFIGURATION_REGISTER;
i2cBuffer[1] = config_reg>>8;
i2cBuffer[2] = config_reg&0xFF;
/* Send the new value of the configuration register */
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 3, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send/write the new FullScale-configuration to OPT3001.");
return ret;
}
else
{
switch(scale)
{
case FULL_SCALE_RANGE_LUX_40:
ESP_LOGI(TAG, "The new FullScale-configurations (40) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_82:
ESP_LOGI(TAG, "The new FullScale-configurations (82) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_164:
ESP_LOGI(TAG, "The new FullScale-configurations (164) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_327:
ESP_LOGI(TAG, "The new FullScale-configurations (327) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_655:
ESP_LOGI(TAG, "The new FullScale-configurations (655) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_1314:
ESP_LOGI(TAG, "The new FullScale-configurations (1314) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_2621:
ESP_LOGI(TAG, "The new FullScale-configurations (2621) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_5241:
ESP_LOGI(TAG, "The new FullScale-configurations (5241) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_10483:
ESP_LOGI(TAG, "The new FullScale-configurations (10483) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_20966:
ESP_LOGI(TAG, "The new FullScale-configurations (20966) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_41933:
ESP_LOGI(TAG, "The new FullScale-configurations (41933) have been written to OPT3001 successfully");
break;
case FULL_SCALE_RANGE_LUX_83865:
ESP_LOGI(TAG, "The new FullScale-configurations (83865) have been written to OPT3001 successfully");
break;
}
}
/* Set the light_full_scale that will be used in the result calculation */
light_full_scale = 0.01*pow(2,scale);
ulp_light_exponent = scale;
return ret;
}
esp_err_t i2c_opt3001_set_conversion_time(lightConversionTime_t CTime)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[3];
/* Read the configuration register*/
uint16_t config_reg = i2c_opt3001_fetch_configuration();
/* Check if MCU failed to read the configuration register */
if(0xFFFF == config_reg)
{
return ESP_FAIL;
}
/* Set the corresponding bits for the conversion-time in the configuration register */
switch(CTime)
{
case CONVERSION_TIME_100Ms: config_reg = config_reg & (~(1<<11)); break;
case CONVERSION_TIME_800Ms: config_reg = config_reg | (1<<11); break;
}
/* Send the new values for the configuration register */
i2cBuffer[0] = CONFIGURATION_REGISTER;
i2cBuffer[1] = config_reg>>8;
i2cBuffer[2] = config_reg&0xFF;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 3, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send/write the new Time-configuration to OPT3001.");
return ret;
}
else
{
//ESP_LOGI(TAG, "The new Time-configurations have been written to OPT3001 successfully");
}
return ret;
}
esp_err_t i2c_opt3001_set_conversion_mode(lightConversionMode_t CMode)
{
/* 1- Creating i2c buffer for sending and receiving */
uint8_t i2cBuffer[3];
/* Read the configuration register*/
uint16_t config_reg = i2c_opt3001_fetch_configuration();
/* Check if MCU failed to read the configuration register */
if(0xFFFF == config_reg)
{
return ESP_FAIL;
}
/* Set the corresponding bits for the conversion-mode in the configuration register */
switch(CMode)
{
case SHUT_DOWN_CONVERSION_MODE:
config_reg = config_reg & (~(1<<9));
config_reg = config_reg & (~(1<<10));
break;
case SINGLE_SHOT_CONVERSION_MODE:
config_reg = config_reg | (1<<9);
config_reg = config_reg & (~(1<<10));
break;
case CONTINUOUS_CONVERSION_MODE:
config_reg = config_reg | (1<<9);
config_reg = config_reg | (1<<10);
break;
}
/* Send the new values for the configuration register */
i2cBuffer[0] = CONFIGURATION_REGISTER;
i2cBuffer[1] = config_reg>>8;
i2cBuffer[2] = config_reg&0xFF;
esp_err_t ret = i2c_master_write_to_device(I2C_MASTER_NUM, OPT3001_ADDR, &i2cBuffer[0], 3, (I2C_MASTER_TIMEOUT_MS));
if(ret != ESP_OK)
{
ESP_LOGI(TAG, "Failed to send/write the new mode-configuration to OPT3001.");
return ret;
}
else
{
//ESP_LOGI(TAG, "The new mode-configurations have been written to OPT3001 successfully");
}
return ret;
}