I have a system of sensors connected to an STM32 chip, all working via I2C and 3.3V.
I’ve created interface libraries for my sensors, specifically the temperature and accelerometer ones. However, when I read the values measured by the sensors, I came across a strange result.
The values are being printed inside my void steup:
Starting...
Scanning I2C bus:
Device found at 0x18
Device found at 0x1F
Device found at 0x50
Device found at 0x51
Device found at 0x7C
I2C scan completed.
Ready KX122
Ready MCP9808
Error in MAX17048 connection
Ready FRAM
Ready!
Next Memory Adds: 0
Starting Temperature Reading:
Temp:
Temp: 1077936128
Starting Battery Reading:
Failed to read voltage
Failed to read SOC
Bat: 0
RMS Accel: -1067319296, 0, 1081114624
Starting Vibration Reading:
Main.c
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "i2c.h"
#include "spi.h"
#include "usart.h"
#include "gpio.h"
#include "stm32l0xx.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "stm32l0xx_hal.h"
#include "math.h"
#include "string.h"
#include "stdio.h"
#include "LORA.h"
#include "FRAM.h"
#include "KX122.h"
#include "MCP9808.h"
#include "MAX17048.h"
#include "BrasensFirmware.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
#define SENSOR_KEY "1111A"
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
#define DEBUG_PRINT(msg) HAL_UART_Transmit(&huart1, (uint8_t*)msg, strlen(msg), HAL_MAX_DELAY)
#define min(a, b) ((a) < (b) ? (a) : (b))
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
Transmission_Data data;
Transmission_VibrationPackage vibrationPackage;
unsigned int sampling_period_us;
unsigned long data_sender_period;
int package_factor = 0;
int acc_sample_factor = 0;
FRAM_Metadata metadata;
uint32_t sizeInBytes = 0;
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
void writeVibrationInformation(void);
void setup(void);
void readAndSendFRAMData(void);
void loop(void);
void sendVibrationPackage(Transmission_VibrationPackage sendingVibrationPackage);
void sendData(Transmission_Data sendingData);
uint32_t micros(void);
uint32_t millis(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void) {
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/* MCU Configuration--------------------------------------------------------*/
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
/* USER CODE BEGIN Init */
/* USER CODE END Init */
/* Configure the system clock */
SystemClock_Config();
/* USER CODE BEGIN SysInit */
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_I2C1_Init();
MX_SPI1_Init();
MX_USART1_UART_Init();
/* USER CODE BEGIN 2 */
setup();
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1) {
/* USER CODE END WHILE */
loop();
/* USER CODE BEGIN 3 */
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void) {
RCC_OscInitTypeDef RCC_OscInitStruct = { 0 };
RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 };
RCC_PeriphCLKInitTypeDef PeriphClkInit = { 0 };
/** Configure the main internal regulator output voltage
*/
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_MSI;
RCC_OscInitStruct.MSIState = RCC_MSI_ON;
RCC_OscInitStruct.MSICalibrationValue = 0;
RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_5;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
Error_Handler();
}
/** Initializes the CPU, AHB and APB buses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK
| RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_MSI;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) {
Error_Handler();
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1
| RCC_PERIPHCLK_I2C1;
PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_PCLK1;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) {
Error_Handler();
}
}
/* USER CODE BEGIN 4 */
uint16_t address = 0;
unsigned long writeMicroseconds;
int current_sample = 0;
void writeVibrationInformation() {
data.rms_accel[0] = 0.0;
data.rms_accel[1] = 0.0;
data.rms_accel[2] = 0.0;
data.rms_vel[0] = 0.0;
data.rms_vel[1] = 0.0;
data.rms_vel[2] = 0.0;
float velocity_x = 0.0;
float velocity_y = 0.0;
float velocity_z = 0.0;
int d = 0;
int count = 0;
for (int i = 0; i < SAMPLES; i++) {
writeMicroseconds = micros();
Vibration vibration = KX122_ReadAccelData(&hi2c1);
count++;
FRAM_WriteFloat(&hi2c1, &metadata,
address + SAMPLES * 0 * sizeof(float), vibration.x);
FRAM_WriteFloat(&hi2c1, &metadata,
address + SAMPLES * 1 * sizeof(float), vibration.y);
FRAM_WriteFloat(&hi2c1, &metadata,
address + SAMPLES * 2 * sizeof(float), vibration.z);
address += sizeof(float);
d++;
count = 0;
data.rms_accel[0] += (vibration.x * vibration.x);
data.rms_accel[1] += (vibration.y * vibration.y);
data.rms_accel[2] += (vibration.z * vibration.z);
float deltaTime = sampling_period_us / 1e6;
velocity_x += vibration.x * deltaTime; //Ax * dT
velocity_y += vibration.y * deltaTime; //Ay * dT
velocity_z += vibration.z * deltaTime; //Az * dT
data.rms_vel[0] += (velocity_x * velocity_x);
data.rms_vel[1] += (velocity_y * velocity_y);
data.rms_vel[2] += (velocity_z * velocity_z);
while (micros() < (writeMicroseconds + sampling_period_us)) {
}
}
data.rms_accel[0] = sqrt(data.rms_accel[0] / SAMPLES);
data.rms_accel[1] = sqrt(data.rms_accel[1] / SAMPLES);
data.rms_accel[2] = sqrt(data.rms_accel[2] / SAMPLES);
data.rms_vel[0] = sqrt(data.rms_vel[0] / SAMPLES);
data.rms_vel[1] = sqrt(data.rms_vel[1] / SAMPLES);
data.rms_vel[2] = sqrt(data.rms_vel[2] / SAMPLES);
char buffer[256];
snprintf(buffer, sizeof(buffer),
"RMS Accel: %d, %d, %drnRMS Vel: %d, %d, %drn",
data.rms_accel[0], data.rms_accel[1], data.rms_accel[2],
data.rms_vel[0], data.rms_vel[1], data.rms_vel[2]);
DEBUG_PRINT(buffer);
}
HAL_StatusTypeDef MCP9808_ReadTemperature_LowPower(double *temperature) {
HAL_StatusTypeDef status;
status = MCP9808_Wake(&hi2c1);
if (status != HAL_OK) {
return status;
}
HAL_Delay(50);
status = MCP9808_ReadTemperature(&hi2c1, temperature);
char buffer[256];
snprintf(buffer, sizeof(buffer),
"Temp: %drn", temperature);
DEBUG_PRINT(buffer);
if (status != HAL_OK) {
return status;
}
status = MCP9808_Shutdown(&hi2c1);
return status;
}
void readBatteryData(uint16_t* soc) {
uint16_t voltage;
char msg[64];
if (MAX17048_ReadVoltage(&hi2c1, &voltage) == HAL_OK) {
snprintf(msg, sizeof(msg), "Voltage: %u mVrn", voltage);
DEBUG_PRINT(msg);
} else {
DEBUG_PRINT("Failed to read voltagern");
}
if (MAX17048_ReadSOC(&hi2c1, soc) == HAL_OK) {
snprintf(msg, sizeof(msg), "State of Charge: %u%%rn", *soc);
DEBUG_PRINT(msg);
} else {
DEBUG_PRINT("Failed to read SOCrn");
}
}
void I2C_Scan() {
char msg[64];
HAL_StatusTypeDef result;
uint8_t i;
DEBUG_PRINT("Scanning I2C bus:rn");
for (i = 1; i < 128; i++) {
/*
* A HAL_I2C_IsDeviceReady() é utilizada para verificar se um dispositivo está
* presente no endereço I2C especificado.
* Os parâmetros são:
* - ponteiro para a handle do I2C
* - endereço do dispositivo I2C
* - tentativas de comunicação
* - tempo máximo de espera
*/
result = HAL_I2C_IsDeviceReady(&hi2c1, (uint16_t)(i << 1), 1, 10);
if (result == HAL_OK) {
snprintf(msg, sizeof(msg), "Device found at 0x%02Xrn", i);
DEBUG_PRINT(msg);
} else {
}
}
DEBUG_PRINT("I2C scan completed.rn");
}
void setup() {
DEBUG_PRINT("Starting...rn");
I2C_Scan();
if(KX122_Init(&hi2c1) != HAL_ERROR)
DEBUG_PRINT("Ready KX122rn");
else
DEBUG_PRINT("Error in KX122 connectionrn");
if(MCP9808_Init(&hi2c1) != HAL_ERROR)
DEBUG_PRINT("Ready MCP9808rn");
else
DEBUG_PRINT("Error in MCP9808 connectionrn");
if(MAX17048_Init(&hi2c1) != HAL_ERROR)
DEBUG_PRINT("Ready MAX17048rn");
else
DEBUG_PRINT("Error in MAX17048 connectionrn");
if(FRAM_Init(&hi2c1) != HAL_ERROR)
DEBUG_PRINT("Ready FRAMrn");
else
DEBUG_PRINT("Error in FRAM connectionrn");
//if(LoRa_Init(&hspi1) != HAL_ERROR)
//DEBUG_PRINT("Read LoRarn");
//else
//DEBUG_PRINT("Error in LoRa connectionrn");
DEBUG_PRINT("Ready!rn");
FRAM_InitMetadata(&metadata);
char buffer[50];
snprintf(buffer, sizeof(buffer), "Next Memory Adds: %drn", metadata.nextFreeAddress);
DEBUG_PRINT(buffer);
package_factor = 3
* ceil((float) (SAMPLES) / (float) TRANSMISSION_DATA_PACKAGE);
data_sender_period = round(
1000 * ((float) DATA_TRANSMISSION_PERIOD / (float) package_factor));
sampling_period_us = round(1000000 * (SAMPLES / (float) ACC_DATA_RATE));
acc_sample_factor = floor((float) ACC_DATA_RATE / (float) SAMPLES);
sizeInBytes = FRAM_MEMORY_SIZE;
FRAM_Format(&hi2c1, &metadata);
DEBUG_PRINT("Starting Temperature Reading:rn");
double temp;
MCP9808_ReadTemperature_LowPower(&temp);
char bufferTemp[50];
snprintf(bufferTemp, sizeof(bufferTemp),
"Temp: %drn",temp);
DEBUG_PRINT(bufferTemp);
DEBUG_PRINT("Starting Battery Reading:rn");
int16_t bat =0;
readBatteryData(&bat);
char bufferBat[50];
snprintf(bufferBat, sizeof(bufferBat),
"Bat: %drn",bat);
DEBUG_PRINT(bufferBat);
Vibration vibration = KX122_ReadAccelData(&hi2c1);
char bufferVib[50];
snprintf(bufferVib, sizeof(bufferVib),
"RMS Accel: %d, %d, %drn",
vibration.x, vibration.y, vibration.z);
DEBUG_PRINT(bufferVib);
//
DEBUG_PRINT("Starting Vibration Reading:rn");
writeVibrationInformation();
}
unsigned long readMilliseconds;
bool energy_save = false;
float temperatureValue;
int current_package = 0;
int reset_counter = 0;
bool sendDataDelay = false;
int axis = 0;
void readAndSendFRAMData() {
if (energy_save) {
readMilliseconds = millis();
sendDataDelay = true;
energy_save = false;
} else if (millis() > (readMilliseconds + data_sender_period)) {
sendDataDelay = true;
}
if (current_package >= (2 * package_factor / 3))
axis = 2;
else if (current_package >= (package_factor / 3))
axis = 1;
else
axis = 0;
if (sendDataDelay) {
int start = TRANSMISSION_DATA_PACKAGE * current_package
- TRANSMISSION_DATA_PACKAGE * axis * package_factor / 3;
int end = (start + TRANSMISSION_DATA_PACKAGE);
if (current_package > 0)
start += 1;
for (int i = start; i <= end; i++) {
uint16_t address = i * sizeof(float)
+ SAMPLES * axis * sizeof(float);
float value = 0.0;
if (SAMPLES >= i) {
FRAM_ReadFloat(&hi2c1, address, &value);
}
vibrationPackage.dataPackage[i - start] = value;
}
strncpy(vibrationPackage.key, SENSOR_KEY, sizeof(vibrationPackage.key));
vibrationPackage.type = 'P';
vibrationPackage.start = start;
vibrationPackage.end = min(end, SAMPLES);
vibrationPackage.axis = axis;
LoRa_Idle(&hspi1);
sendVibrationPackage(vibrationPackage);
readMilliseconds = millis();
sendDataDelay = false;
//if (report) {
//temperatureValue += readTemperature() / package_factor;
current_package++;
//reset_counter = 0;
LoRa_Sleep(&hspi1);
energy_save = true;
}
}
void loop() {
readAndSendFRAMData();
if (current_package >= package_factor) {
writeVibrationInformation();
temperatureValue = 0;
MCP9808_ReadTemperature_LowPower( &temperatureValue);
data.temperature = temperatureValue;
strncpy(data.key, SENSOR_KEY, sizeof(data.key));
data.type = 'D';
uint16_t soc = 0;
readBatteryData(&soc); // Passing the address of soc
data.battery = soc;
sendData(data);
current_package = 0;
}
}
void sendVibrationPackage(Transmission_VibrationPackage sendingVibrationPackage) {
LoRa_Idle(&hspi1);
uint8_t buffer[sizeof(Transmission_VibrationPackage)];
memcpy(buffer, &sendingVibrationPackage,
sizeof(Transmission_VibrationPackage));
LoRa_Transmit(&hspi1, buffer, sizeof(Transmission_VibrationPackage));
LoRa_Sleep(&hspi1);
}
void sendData(Transmission_Data sendingData) {
LoRa_Idle(&hspi1);
uint8_t buffer[sizeof(Transmission_Data)];
memcpy(buffer, &sendingData, sizeof(Transmission_Data));
LoRa_Transmit(&hspi1, buffer, sizeof(Transmission_Data));
LoRa_Sleep(&hspi1);
}
Accelerometer Library:
/*
* KX122.c
*
* Created on: Jun 7, 2024
* Author: Matheus Markies
*/
#include "KX122.h"
static HAL_StatusTypeDef KX122_WriteRegister(I2C_HandleTypeDef *hi2c,
uint8_t reg, uint8_t value);
static HAL_StatusTypeDef KX122_ReadRegister(I2C_HandleTypeDef *hi2c,
uint8_t reg, uint8_t *data);
HAL_StatusTypeDef KX122_Init(I2C_HandleTypeDef *hi2c) {
if (KX122_WriteRegister(hi2c, 0x18, 0x00) != HAL_OK) return HAL_ERROR;
if (KX122_WriteRegister(hi2c, 0x18, 0x80) != HAL_OK) return HAL_ERROR;
if (KX122_WriteRegister(hi2c, 0x19, 0x00) != HAL_OK) return HAL_ERROR;
if (KX122_WriteRegister(hi2c, 0x1A, 0x00) != HAL_OK) return HAL_ERROR;
if (KX122_WriteRegister(hi2c, KX122_ODR_SPEED, 0x0F) != HAL_OK) return HAL_ERROR;
return HAL_OK;
}
Vibration KX122_ReadAccelData(I2C_HandleTypeDef *hi2c) {
uint8_t data[6];
Vibration vib = {0};
if (KX122_ReadRegister(hi2c, KX122_XOUT_L, &data[0]) != HAL_OK) return vib;
if (KX122_ReadRegister(hi2c, KX122_XOUT_H, &data[1]) != HAL_OK) return vib;
if (KX122_ReadRegister(hi2c, KX122_YOUT_L, &data[2]) != HAL_OK) return vib;
if (KX122_ReadRegister(hi2c, KX122_YOUT_H, &data[3]) != HAL_OK) return vib;
if (KX122_ReadRegister(hi2c, KX122_ZOUT_L, &data[4]) != HAL_OK) return vib;
if (KX122_ReadRegister(hi2c, KX122_ZOUT_H, &data[5]) != HAL_OK) return vib;
int16_t raw_x = (int16_t)((data[1] << 8) | data[0]);
int16_t raw_y = (int16_t)((data[3] << 8) | data[2]);
int16_t raw_z = (int16_t)((data[5] << 8) | data[4]);
// Converting raw data to Gs (assuming default sensitivity)
double sensitivity = 0.000061; // 61 μg/LSB for ±2g range
vib.x = raw_x * sensitivity;
vib.y = raw_y * sensitivity;
vib.z = raw_z * sensitivity;
return vib;
}
static HAL_StatusTypeDef KX122_WriteRegister(I2C_HandleTypeDef *hi2c, uint8_t reg, uint8_t value) {
uint8_t data[2] = { reg, value };
return HAL_I2C_Master_Transmit(hi2c, KX122_I2C_ADDRESS << 1, data, 2, HAL_MAX_DELAY);
}
static HAL_StatusTypeDef KX122_ReadRegister(I2C_HandleTypeDef *hi2c, uint8_t reg, uint8_t *data) {
HAL_StatusTypeDef status = HAL_I2C_Master_Transmit(hi2c, KX122_I2C_ADDRESS << 1, ®, 1, HAL_MAX_DELAY);
if (status == HAL_OK) {
status = HAL_I2C_Master_Receive(hi2c, KX122_I2C_ADDRESS << 1, data, 1, HAL_MAX_DELAY);
}
return status;
}
Temperature Library:
/*
* MCP9808.c
*
* Created on: Jun 9, 2024
* Author: Matheus Markies
*/
#include "MCP9808.h"
static HAL_StatusTypeDef MCP9808_ReadRegister(I2C_HandleTypeDef *hi2c, uint8_t reg, uint8_t *data, uint8_t len);
static HAL_StatusTypeDef MCP9808_WriteRegister_16(I2C_HandleTypeDef *hi2c, uint8_t reg, uint16_t value);
static HAL_StatusTypeDef MCP9808_WriteRegister(I2C_HandleTypeDef *hi2c, uint8_t reg, uint8_t *data, uint8_t len);
static HAL_StatusTypeDef MCP9808_ReadRegister_16(I2C_HandleTypeDef *hi2c, uint8_t reg, uint16_t *value);
HAL_StatusTypeDef MCP9808_Init(I2C_HandleTypeDef *hi2c) {
uint16_t manuf_id, device_id;
if (MCP9808_ReadRegister_16(hi2c, MCP9808_REG_MANUF_ID, &manuf_id) != HAL_OK) {
return HAL_ERROR;
}
if (manuf_id != 0x0054) {
return HAL_ERROR;
}
if (MCP9808_ReadRegister_16(hi2c, MCP9808_REG_DEVICE_ID, &device_id) != HAL_OK) {
return HAL_ERROR;
}
if (device_id != 0x0400) {
return HAL_ERROR;
}
MCP9808_WriteRegister_16(hi2c, MCP9808_REG_CONFIG, 0x0000);
return HAL_OK;
}
HAL_StatusTypeDef MCP9808_Shutdown(I2C_HandleTypeDef *hi2c) {
uint16_t conf_register;
uint16_t conf_shutdown;
if (MCP9808_ReadRegister_16(hi2c, MCP9808_REG_CONFIG, &conf_register) != HAL_OK) {
return HAL_ERROR;
}
conf_shutdown = conf_register | MCP9808_REG_CONFIG_SHUTDOWN;
return MCP9808_WriteRegister_16(hi2c, MCP9808_REG_CONFIG, conf_shutdown);
}
HAL_StatusTypeDef MCP9808_Wake(I2C_HandleTypeDef *hi2c) {
uint16_t conf_register;
uint16_t conf_shutdown;
if (MCP9808_ReadRegister_16(hi2c, MCP9808_REG_CONFIG, &conf_register) != HAL_OK) {
return HAL_ERROR;
}
conf_shutdown = conf_register & ~MCP9808_REG_CONFIG_SHUTDOWN;
return MCP9808_WriteRegister_16(hi2c, MCP9808_REG_CONFIG, conf_shutdown);
}
uint8_t MCP9808_GetResolution(I2C_HandleTypeDef *hi2c) {
uint8_t data;
MCP9808_ReadRegister(hi2c, MCP9808_REG_RESOLUTION, &data, 2);
return data;
}
HAL_StatusTypeDef MCP9808_SetResolution(I2C_HandleTypeDef *hi2c, uint8_t value) {
return MCP9808_WriteRegister(hi2c, MCP9808_REG_RESOLUTION, &value, 1);
}
HAL_StatusTypeDef MCP9808_ReadTemperature(I2C_HandleTypeDef *hi2c, double *temperature) {
uint8_t temp_data[2];
if (MCP9808_ReadRegister(hi2c, MCP9808_REG_TEMP, temp_data, 2) != HAL_OK) {
return HAL_ERROR;
}
uint16_t raw_temp = (temp_data[0] << 8) | temp_data[1];
raw_temp &= 0x0FFF; // Máscara para os 12 bits de dados
double temp = raw_temp & 0x0FFF;
temp /= 16.0;
if (raw_temp & 0x1000) {
temp -= 256.0;
}
*temperature = temp;
return HAL_OK;
}
static HAL_StatusTypeDef MCP9808_WriteRegister_16(I2C_HandleTypeDef *hi2c, uint8_t reg, uint16_t value) {
uint8_t data[3] = {reg, (value >> 8) & 0xFF, value & 0xFF};
return HAL_I2C_Master_Transmit(hi2c, MCP9808_I2C_ADDRESS << 1, data, 3, HAL_MAX_DELAY);
}
static HAL_StatusTypeDef MCP9808_WriteRegister(I2C_HandleTypeDef *hi2c, uint8_t reg, uint8_t *data, uint8_t len) {
uint8_t buffer[3];
buffer[0] = reg;
for (uint8_t i = 0; i < len; i++) {
buffer[i + 1] = data[i];
}
return HAL_I2C_Master_Transmit(hi2c, MCP9808_I2C_ADDRESS << 1, buffer, len + 1, HAL_MAX_DELAY);
}
static HAL_StatusTypeDef MCP9808_ReadRegister(I2C_HandleTypeDef *hi2c, uint8_t reg, uint8_t *data, uint8_t len) {
HAL_StatusTypeDef status = HAL_I2C_Master_Transmit(hi2c, MCP9808_I2C_ADDRESS << 1, ®, 1, HAL_MAX_DELAY);
if (status == HAL_OK) {
status = HAL_I2C_Master_Receive(hi2c, MCP9808_I2C_ADDRESS << 1, data, len, HAL_MAX_DELAY);
}
return status;
}
static HAL_StatusTypeDef MCP9808_ReadRegister_16(I2C_HandleTypeDef *hi2c, uint8_t reg, uint16_t *value) {
uint8_t data[2];
HAL_StatusTypeDef status = HAL_I2C_Master_Transmit(hi2c, MCP9808_I2C_ADDRESS << 1, ®, 1, HAL_MAX_DELAY);
if (status == HAL_OK) {
status = HAL_I2C_Master_Receive(hi2c, MCP9808_I2C_ADDRESS << 1, data, 2, HAL_MAX_DELAY);
if (status == HAL_OK) {
*value = (data[0] << 8) | data[1];
}
}
return status;
}
Structs:
#ifndef SRC_BRASENSCOMMONS_H_
#define SRC_BRASENSCOMMONS_H_
#define DATA_TRANSMISSION_PERIOD 350
#define TRANSMISSION_DATA_PACKAGE 60
#define SAMPLES 2048 // 2^13 8.192 ou 2^14 16384
typedef struct __attribute__((__packed__)) {
char type; // 'D' para Data
char key[6];
double rms_accel[3];
double rms_vel[3];
double temperature;
double battery;
} Transmission_Data;
typedef struct __attribute__((__packed__)) {
char type; // 'V' para VibrationPackage
char key[6];
int axis; //X = 0, Y = 1, Z = 2
double dataPackage[TRANSMISSION_DATA_PACKAGE];
int start;
int end;
} Transmission_VibrationPackage;
#endif /* SRC_BRASENSCOMMONS_H_ */
I need the correct values to be displayed, I believe there may be an error reading the bytes coming from the sensors.
As you can see, the acceleration and temperature values are all wrong. They should be double values.
Temp: 1077936128
RMS Accel: -1067319296, 0, 1081114626