From d06f3c70f859b52677162a9b8668f4a1b2cc73eb Mon Sep 17 00:00:00 2001
From: jazzpi <jasper@mezzo.de>
Date: Tue, 9 Aug 2022 13:05:36 +0200
Subject: [PATCH] Import/adapt Master_Interface code

---
 Core/Inc/AIR_State_Maschine.h |  10 +-
 Core/Inc/AMS_Errorcodes.h     |  14 ++-
 Core/Inc/CAN_Communication.h  |  37 +++++--
 Core/Inc/Check_Shunt_Limits.h |  36 ++++++
 Core/Inc/Fan_Control.h        |  16 +++
 Core/Inc/Slave_Monitoring.h   |  25 +++--
 Core/Inc/SoC_Estimation.h     |  15 +++
 Core/Inc/main.h               |   2 +-
 Core/Inc/util.h               |  17 +++
 Core/Src/AIR_State_Maschine.c | 136 +++++++++--------------
 Core/Src/CAN_Communication.c  | 203 ++++++++++++++++++++++++----------
 Core/Src/Check_Shunt_Limits.c |  30 +++++
 Core/Src/Clock_Sync.c         |   4 +-
 Core/Src/Fan_Control.c        |  25 +++++
 Core/Src/Slave_Monitoring.c   |  72 +++++++++---
 Core/Src/SoC_Estimation.c     |  70 ++++++++++++
 Core/Src/main.c               |  35 ++++--
 Core/Src/util.c               |  27 +++++
 STM32Make.make                |   4 +
 19 files changed, 586 insertions(+), 192 deletions(-)
 create mode 100644 Core/Inc/Check_Shunt_Limits.h
 create mode 100644 Core/Inc/Fan_Control.h
 create mode 100644 Core/Inc/SoC_Estimation.h
 create mode 100644 Core/Inc/util.h
 create mode 100644 Core/Src/Check_Shunt_Limits.c
 create mode 100644 Core/Src/Fan_Control.c
 create mode 100644 Core/Src/SoC_Estimation.c
 create mode 100644 Core/Src/util.c

diff --git a/Core/Inc/AIR_State_Maschine.h b/Core/Inc/AIR_State_Maschine.h
index 5f285eb..76de640 100644
--- a/Core/Inc/AIR_State_Maschine.h
+++ b/Core/Inc/AIR_State_Maschine.h
@@ -40,13 +40,13 @@ typedef struct {
   uint32_t chargingCheckTimestamp;
 
 } AIRStateHandler;
+extern AIRStateHandler airstate;
 
-AIRStateHandler init_AIR_State_Maschine();
+void init_AIR_State_Maschine();
 
-void Update_AIR_Info(AIRStateHandler* airstate);
-uint8_t Update_AIR_State(AIRStateHandler* airstate);
-void Activate_TS(AIRStateHandler* airstate);
-void Deactivate_TS(AIRStateHandler* airstate);
+uint8_t Update_AIR_State();
+void Activate_TS();
+void Deactivate_TS();
 
 void AIR_Precharge_Position();
 void AIR_Inactive_Position();
diff --git a/Core/Inc/AMS_Errorcodes.h b/Core/Inc/AMS_Errorcodes.h
index 63b3bb5..375a12f 100644
--- a/Core/Inc/AMS_Errorcodes.h
+++ b/Core/Inc/AMS_Errorcodes.h
@@ -10,9 +10,15 @@
 
 #include "main.h"
 
-#define SlavesTimeoutError 1
-#define SlavesErrorFrameError 2
-#define SLAVES_FRAME_TIMEOUT_ERROR 3
-#define SLAVES_TOO_FEW_TEMPS 4
+#define AMS_ERROR_SLAVE_TIMEOUT 1
+#define AMS_ERROR_SLAVE_PANIC 2
+#define AMS_ERROR_SLAVE_FRAME_TIMEOUT 3
+#define AMS_ERROR_SLAVE_TOO_FEW_TEMPS 4
+#define AMS_ERROR_SHUNT_TIMEOUT 6
+#define AMS_ERROR_MASTER_THRESH 7
+#define AMS_ERRORARG_MASTER_THRESH_UT 0
+#define AMS_ERRORARG_MASTER_THRESH_OT 1
+#define AMS_ERRORARG_MASTER_THRESH_UV 2
+#define AMS_ERRORARG_MASTER_THRESH_OV 3
 
 #endif /* INC_AMS_ERRORCODES_H_ */
diff --git a/Core/Inc/CAN_Communication.h b/Core/Inc/CAN_Communication.h
index efe258e..e202f7f 100644
--- a/Core/Inc/CAN_Communication.h
+++ b/Core/Inc/CAN_Communication.h
@@ -17,13 +17,30 @@
 
 #define CANFRAMEBUFFERSIZE 512
 
+#define CAN_ID_SLAVE_EMERGENCY 0x001
+#define CAN_ID_CLOCK_SYNC 0x002
+#define CAN_ID_AMS_STATUS 0x0A
+#define CAN_ID_AUTOBOX_INFO 0x0B
+#define CAN_ID_MASTER_HEARTBEAT 0x010
+#define CAN_ID_SLAVE_EEPROM_WRITE 0x020
+#define CAN_ID_AMS_PANIC 0x42
+
+#define CAN_ID_START_CHARGING 0x446
+
+#define CAN_ID_SHUNT_BASE 0x520
+#define CAN_MASK_SHUNT 0xFF0
+#define CAN_ID_SHUNT_CURRENT 0x521
+#define CAN_ID_SHUNT_VOLTAGE_1 0x522
+#define CAN_ID_SHUNT_VOLTAGE_2 0x523
+#define CAN_ID_SHUNT_VOLTAGE_3 0x524
+#define CAN_ID_SHUNT_BUSBAR_TEMP 0x525
+#define CAN_ID_SHUNT_POWER 0x526
+#define CAN_ID_SHUNT_AMPERE_SECONDS 0x527
+#define CAN_ID_SHUNT_ENERGY 0x528
+
 // Frame ID = Base Address + Slave ID + MessageNr.
-#define SLAVE_STATUS_BASE_ADDRESS 0x600
-#define SLAVE_CMD_BASE_ADDRESS 0x500  //
-#define SLAVE_EMERGENCY_ADDRESS 0x001 // Emergency Frame
-#define CLOCK_SYNC_ADDRESS 0x002
-#define MASTER_HEARTBEAT_ADDRESS 0x010
-#define SLAVE_EEPROM_WRITE_ADDRESS 0x020
+#define CAN_ID_SLAVE_STATUS_BASE 0x600
+#define CAN_MASK_SLAVE_STATUS 0xF00
 
 typedef struct {
   int16_t FrameID;
@@ -47,6 +64,12 @@ void CAN_Init(FDCAN_HandleTypeDef* hcan);
 uint8_t CAN_Receive(FDCAN_HandleTypeDef* hcan);
 uint8_t CAN_Transmit(FDCAN_HandleTypeDef* hcan, uint16_t frameid,
                      uint8_t* buffer, uint8_t datalen);
-void updateSlaveInfo(uint8_t slaveID, uint8_t MessageID, canFrame rxFrame);
+
+void CAN_SendAbxStatus(FDCAN_HandleTypeDef* hcan);
+void CAN_SendAMSPanic(FDCAN_HandleTypeDef* hcan, AMSErrorHandle* error);
+
+void CAN_HandleShuntMsg(canFrame* rxFrame);
+void CAN_HandleSlaveStatus(canFrame* rxFrame);
+void CAN_HandleSlaveEmergency(canFrame* rxFrame);
 
 #endif /* INC_CAN_COMMUNICATION_H_ */
diff --git a/Core/Inc/Check_Shunt_Limits.h b/Core/Inc/Check_Shunt_Limits.h
new file mode 100644
index 0000000..3f43a2c
--- /dev/null
+++ b/Core/Inc/Check_Shunt_Limits.h
@@ -0,0 +1,36 @@
+/*
+ * Check_Shunt_Limits.h
+ *
+ *  Created on: Jun 16, 2022
+ *      Author: max
+ */
+
+#ifndef INC_CHECK_SHUNT_LIMITS_H_
+#define INC_CHECK_SHUNT_LIMITS_H_
+
+#include "CAN_Communication.h"
+#include "main.h"
+
+#include <stdint.h>
+
+#define SHUNT_OVERCURRENT 0x0FFFFFFF // Shunt Overcurrent Limit
+#define SHUNT_TIMEOUT 500            // Timeout after 500ms
+#define SHUNT_OVERTEMP 0xFFFFFFFF    // Overtermperature of the Busbar
+
+typedef struct {
+  int32_t current;
+  int32_t voltage1;
+  int32_t voltage2;
+  int32_t voltage3;
+  int32_t busbartemp;
+  int32_t power;
+  int32_t energy;
+  int32_t ampere_seconds;
+
+  uint32_t last_message;
+} ShuntData;
+extern ShuntData shunt_data;
+
+void CheckShuntLimits();
+
+#endif /* INC_CHECK_SHUNT_LIMITS_H_ */
diff --git a/Core/Inc/Fan_Control.h b/Core/Inc/Fan_Control.h
new file mode 100644
index 0000000..0ffcc49
--- /dev/null
+++ b/Core/Inc/Fan_Control.h
@@ -0,0 +1,16 @@
+/*
+ * Fan_Control.h
+ *
+ *  Created on: Jun 23, 2022
+ *      Author: max
+ */
+
+#ifndef INC_FAN_CONTROL_H_
+#define INC_FAN_CONTROL_H_
+
+#include "main.h"
+
+void Temp_Ctrl_Init(TIM_HandleTypeDef* htim, uint32_t channel);
+void Temp_Ctrl_Loop();
+
+#endif /* INC_FAN_CONTROL_H_ */
diff --git a/Core/Inc/Slave_Monitoring.h b/Core/Inc/Slave_Monitoring.h
index 362453e..1cf7d30 100644
--- a/Core/Inc/Slave_Monitoring.h
+++ b/Core/Inc/Slave_Monitoring.h
@@ -14,20 +14,28 @@
 
 #include "stm32g431xx.h"
 
-#define NUMBEROFSLAVES 9
-#define NUMBEROFCELLS 10
-#define NUMBEROFTEMPS 32
+#include <stdint.h>
+
+#define N_SLAVES 9
+#define N_CELLS_SERIES 10
+#define N_CELLS_PARALLEL 9
+#define N_TEMP_SENSORS 32
 
 #define SLAVETIMEOUT 5000
 #define SLAVE_HEARTBEAT_FRAMES 11
 // 30% * 90 = 27, each sensor measures 2 cells
 #define SLAVE_MIN_TEMP_SENSORS 14
 
+#define THRESH_UV 32768 /* 2.5V */
+#define THRESH_OV 55050 /* 4.2V */
+#define THRESH_UT 0     /* 0C */
+#define THRESH_OT 880   /* 55C */
+
 typedef struct {
 
   uint16_t slaveID;
-  uint16_t cellVoltages[NUMBEROFCELLS];
-  uint16_t cellTemps[NUMBEROFTEMPS];
+  uint16_t cellVoltages[N_CELLS_SERIES];
+  uint16_t cellTemps[N_TEMP_SENSORS];
   uint32_t timestamp;
   uint8_t error;
   uint8_t timeout;
@@ -36,9 +44,12 @@ typedef struct {
 
 } SlaveHandler;
 
-extern SlaveHandler slaves[NUMBEROFSLAVES];
+extern SlaveHandler slaves[N_SLAVES];
+
+extern uint16_t min_voltage, max_voltage;
+extern int16_t min_temp, max_temp;
 
 void initSlaves();
-uint8_t checkSlaveTimeout();
+uint8_t checkSlaves();
 
 #endif /* INC_SLAVE_MONITORING_H_ */
diff --git a/Core/Inc/SoC_Estimation.h b/Core/Inc/SoC_Estimation.h
new file mode 100644
index 0000000..1521580
--- /dev/null
+++ b/Core/Inc/SoC_Estimation.h
@@ -0,0 +1,15 @@
+#ifndef INC_SOC_ESTIMATION_H
+#define INC_SOC_ESTIMATION_H
+
+#include <stdint.h>
+
+#define SOCE_SHUNT_CURRENT_OFF_THRESH 20                  /* mA */
+#define CELL_VOLTAGE_CONVERSION_FACTOR (5.0f / 65535)     /* V/quantum */
+#define BATTERY_CAPACITY (N_CELLS_PARALLEL * 2.5f * 3600) /* As */
+
+extern uint8_t current_soc;
+
+void estimate_soc();
+float calculate_soc_for_ocv(float ocv);
+
+#endif // INC_SOC_ESTIMATION_H
diff --git a/Core/Inc/main.h b/Core/Inc/main.h
index dd1814f..5eb01a0 100644
--- a/Core/Inc/main.h
+++ b/Core/Inc/main.h
@@ -38,7 +38,7 @@ extern "C" {
 /* USER CODE BEGIN ET */
 typedef struct {
   uint8_t errorcode;
-  uint8_t errorarg[8];
+  uint8_t errorarg[7];
 } AMSErrorHandle;
 /* USER CODE END ET */
 
diff --git a/Core/Inc/util.h b/Core/Inc/util.h
new file mode 100644
index 0000000..8e451da
--- /dev/null
+++ b/Core/Inc/util.h
@@ -0,0 +1,17 @@
+#ifndef INC_UTIL_H
+#define INC_UTIL_H
+
+#include <stdint.h>
+
+/**
+ * @brief Perform linear interpolation.
+ *
+ * @param n_points Size of source_x and source_y
+ * @param source_x x values for the interpolation source (sorted ascending)
+ * @param source_y y values corresponding to source_x
+ * @param target_x x value that a y value should be interpolated for
+ */
+float interp(uint32_t n_points, const float* source_x, const float* source_y,
+             float target_x);
+
+#endif // INC_UTIL_H
diff --git a/Core/Src/AIR_State_Maschine.c b/Core/Src/AIR_State_Maschine.c
index 20fe32b..46180ae 100644
--- a/Core/Src/AIR_State_Maschine.c
+++ b/Core/Src/AIR_State_Maschine.c
@@ -12,6 +12,8 @@
 #include "stm32g4xx_hal.h"
 #include "stm32g4xx_hal_gpio.h"
 
+AIRStateHandler airstate;
+
 DMA_HandleTypeDef* air_current_dma = {0};
 DMA_HandleTypeDef* sdc_voltage_dma = {0};
 
@@ -22,46 +24,14 @@ static uint32_t pos_air_change_timestamp, neg_air_change_timestamp,
     precharge_change_timestamp;
 static GPIO_PinState neg_air_state, pos_air_state, precharge_state;
 
-AIRStateHandler init_AIR_State_Maschine() {
-  AIRStateHandler airstate = {0};
-
+void init_AIR_State_Maschine() {
   airstate.targetTSState = TS_INACTIVE;
   airstate.currentTSState = TS_INACTIVE;
   airstate.BatteryVoltageBatterySide = 0;
   airstate.BatteryVoltageVehicleSide = 0;
-
-  return airstate;
 }
 
-void Update_AIR_Info(AIRStateHandler* airstate) {
-  uint16_t relay_adc_buffer[4] = {0};
-  uint16_t sdc_adc_buffer[1] = {0};
-
-  /*//HAL_ADC_Start_DMA(air_current_adc, (uint32_t*)relay_adc_buffer, 4);
-  //HAL_ADC_Start_DMA(sdc_voltage_adc, (uint32_t*)sdc_adc_buffer, 1);
-  HAL_ADC_Start(sdc_voltage_adc);
-  HAL_StatusTypeDef status = HAL_ADC_PollForConversion(sdc_voltage_adc, 10);
-  uint32_t adcval1 = HAL_ADC_GetValue(sdc_voltage_adc);
-  HAL_ADC_Stop(sdc_voltage_adc);
-
-  HAL_ADC_Start(air_current_adc);
-  status = HAL_ADC_PollForConversion(air_current_adc, 10);
-  uint32_t adcval2 = HAL_ADC_GetValue(air_current_adc);
-  HAL_ADC_Start(air_current_adc);
-  status = HAL_ADC_PollForConversion(air_current_adc, 10);
-  uint32_t adcval3 = HAL_ADC_GetValue(air_current_adc);
-  HAL_ADC_Start(air_current_adc);
-  status = HAL_ADC_PollForConversion(air_current_adc, 10);
-  uint32_t adcval4 = HAL_ADC_GetValue(air_current_adc);
-  HAL_ADC_Start(air_current_adc);
-  status = HAL_ADC_PollForConversion(air_current_adc, 10);
-  uint32_t adcval5 = HAL_ADC_GetValue(air_current_adc);
-  HAL_ADC_Stop(air_current_adc);*/
-}
-
-uint8_t Update_AIR_State(AIRStateHandler* airstate) {
-  Update_AIR_Info(airstate);
-
+uint8_t Update_AIR_State() {
   //--------------------------------------------------State Transition
   // Rules----------------------------------------------------------
 
@@ -71,124 +41,120 @@ uint8_t Update_AIR_State(AIRStateHandler* airstate) {
           return airstate->currentTSState;
   }*/
 
-  if (airstate->currentTSState == TS_ERROR) // No Escape from TS Error State
+  if (airstate.currentTSState == TS_ERROR) // No Escape from TS Error State
   {
     // Don't change anything, but prevent any other if from being entered
   }
 
-  else if (airstate->targetTSState ==
+  else if (airstate.targetTSState ==
            TS_ERROR) // Error State is Entered if Target State is Error State
   {
-    airstate->currentTSState = TS_ERROR;
+    airstate.currentTSState = TS_ERROR;
   }
 
-  else if ((airstate->currentTSState == TS_INACTIVE) &&
-           (airstate->targetTSState ==
+  else if ((airstate.currentTSState == TS_INACTIVE) &&
+           (airstate.targetTSState ==
             TS_ACTIVE)) // Transition from Inactive to Active via Precharge
   {
-    airstate->currentTSState = TS_PRECHARGE;
-    airstate->precharge95ReachedTimestamp = 0;
+    airstate.currentTSState = TS_PRECHARGE;
+    airstate.precharge95ReachedTimestamp = 0;
   }
 
-  else if ((airstate->currentTSState == TS_INACTIVE) &&
-           (airstate->targetTSState == TS_CHARGING)) {
-    airstate->currentTSState = TS_CHARGING_CHECK;
-    airstate->chargingCheckTimestamp = HAL_GetTick();
+  else if ((airstate.currentTSState == TS_INACTIVE) &&
+           (airstate.targetTSState == TS_CHARGING)) {
+    airstate.currentTSState = TS_CHARGING_CHECK;
+    airstate.chargingCheckTimestamp = HAL_GetTick();
   }
 
   // TODO: Is it correct that we also go from precharge to discharge?
-  else if ((airstate->currentTSState == TS_ACTIVE ||
-            airstate->currentTSState == TS_PRECHARGE ||
-            airstate->currentTSState == TS_CHARGING_CHECK ||
-            airstate->currentTSState == TS_CHARGING) &&
-           (airstate->targetTSState ==
+  else if ((airstate.currentTSState == TS_ACTIVE ||
+            airstate.currentTSState == TS_PRECHARGE ||
+            airstate.currentTSState == TS_CHARGING_CHECK ||
+            airstate.currentTSState == TS_CHARGING) &&
+           (airstate.targetTSState ==
             TS_INACTIVE)) // Transition from Active to Inactive via Discharge
   {
-    airstate->currentTSState = TS_DISCHARGE;
+    airstate.currentTSState = TS_DISCHARGE;
   }
 
-  else if ((airstate->targetTSState == TS_CHARGING) &&
-           (airstate->currentTSState == TS_CHARGING_CHECK)) {
-    if (airstate->BatteryVoltageVehicleSide >
-        airstate->BatteryVoltageBatterySide) {
-      airstate->currentTSState = TS_CHARGING;
-    } else if (HAL_GetTick() > airstate->chargingCheckTimestamp + 2000) {
-      airstate->currentTSState = TS_ERROR;
+  else if ((airstate.targetTSState == TS_CHARGING) &&
+           (airstate.currentTSState == TS_CHARGING_CHECK)) {
+    if (airstate.BatteryVoltageVehicleSide >
+        airstate.BatteryVoltageBatterySide) {
+      airstate.currentTSState = TS_CHARGING;
+    } else if (HAL_GetTick() > airstate.chargingCheckTimestamp + 2000) {
+      airstate.currentTSState = TS_ERROR;
     }
   }
 
-  else if (airstate->currentTSState == TS_CHARGING) {
-    if (airstate->shuntCurrent < 0) {
-      airstate->currentTSState = TS_ERROR;
+  else if (airstate.currentTSState == TS_CHARGING) {
+    if (airstate.shuntCurrent < 0) {
+      airstate.currentTSState = TS_ERROR;
     }
   }
 
-  else if (airstate->currentTSState ==
+  else if (airstate.currentTSState ==
            TS_PRECHARGE) // Change from Precharge to Active at 95% TS Voltage at
                          // Vehicle Side
   {
-    if ((airstate->BatteryVoltageVehicleSide >
+    if ((airstate.BatteryVoltageVehicleSide >
          LOWER_VEHICLE_SIDE_VOLTAGE_LIMIT)) {
-      if (airstate->BatteryVoltageVehicleSide >
-          (airstate->BatteryVoltageBatterySide * 0.95)) {
-        if (airstate->precharge95ReachedTimestamp == 0) {
-          airstate->precharge95ReachedTimestamp = HAL_GetTick();
-        } else if (HAL_GetTick() - airstate->precharge95ReachedTimestamp >=
+      if (airstate.BatteryVoltageVehicleSide >
+          (airstate.BatteryVoltageBatterySide * 0.95)) {
+        if (airstate.precharge95ReachedTimestamp == 0) {
+          airstate.precharge95ReachedTimestamp = HAL_GetTick();
+        } else if (HAL_GetTick() - airstate.precharge95ReachedTimestamp >=
                    PRECHARGE_95_DURATION) {
-          airstate->currentTSState = TS_ACTIVE;
+          airstate.currentTSState = TS_ACTIVE;
         }
       }
     }
   }
 
-  else if (airstate->currentTSState ==
+  else if (airstate.currentTSState ==
            TS_DISCHARGE) // Change from Discharge to Inactive at 95% TS
                          // Voltage at Vehicle Side
   {
-    airstate->currentTSState = TS_INACTIVE;
+    airstate.currentTSState = TS_INACTIVE;
   }
 
   //_-----------------------------------------------AIR
   // Positions--------------------------------------------------------
 
-  if (airstate->currentTSState == TS_PRECHARGE) {
+  if (airstate.currentTSState == TS_PRECHARGE) {
     AIR_Precharge_Position();
   }
 
-  if (airstate->currentTSState == TS_DISCHARGE) {
+  if (airstate.currentTSState == TS_DISCHARGE) {
     AIR_Discharge_Position();
   }
 
-  if (airstate->currentTSState == TS_CHARGING_CHECK) {
+  if (airstate.currentTSState == TS_CHARGING_CHECK) {
     AIR_Precharge_Position();
   }
 
-  if (airstate->currentTSState == TS_CHARGING) {
+  if (airstate.currentTSState == TS_CHARGING) {
     AIR_Active_Position();
   }
 
-  if (airstate->currentTSState == TS_ACTIVE) {
+  if (airstate.currentTSState == TS_ACTIVE) {
     AIR_Active_Position();
   }
 
-  if (airstate->currentTSState == TS_INACTIVE) {
+  if (airstate.currentTSState == TS_INACTIVE) {
     AIR_Inactive_Position();
   }
 
-  if (airstate->currentTSState == TS_ERROR) {
+  if (airstate.currentTSState == TS_ERROR) {
     AIR_Error_Position();
   }
 
-  return airstate->currentTSState;
+  return airstate.currentTSState;
 }
 
-void Activate_TS(AIRStateHandler* airstate) {
-  airstate->targetTSState = TS_ACTIVE;
-}
+void Activate_TS() { airstate.targetTSState = TS_ACTIVE; }
 
-void Deactivate_TS(AIRStateHandler* airstate) {
-  airstate->targetTSState = TS_INACTIVE;
-}
+void Deactivate_TS() { airstate.targetTSState = TS_INACTIVE; }
 
 void AIR_Precharge_Position() {
   Set_Relay_Position(RELAY_PRECHARGE, GPIO_PIN_SET);
diff --git a/Core/Src/CAN_Communication.c b/Core/Src/CAN_Communication.c
index 6223891..e838d9e 100644
--- a/Core/Src/CAN_Communication.c
+++ b/Core/Src/CAN_Communication.c
@@ -7,7 +7,10 @@
 
 #include "CAN_Communication.h"
 
+#include "AIR_State_Maschine.h"
+#include "Check_Shunt_Limits.h"
 #include "Error_Check.h"
+#include "SoC_Estimation.h"
 
 #include "stm32g4xx_hal_fdcan.h"
 
@@ -58,20 +61,21 @@ uint8_t CAN_Receive(FDCAN_HandleTypeDef* hcan) {
       framebufferreadpointer = 0;
     }
 
-    canFrame rxFrame = framebuffer[framebufferreadpointer];
+    canFrame* rxFrame = &framebuffer[framebufferreadpointer];
     frames_read++;
 
-    if ((rxFrame.FrameID & SLAVE_STATUS_BASE_ADDRESS) ==
-        SLAVE_STATUS_BASE_ADDRESS) {
-      uint16_t msg = rxFrame.FrameID - SLAVE_STATUS_BASE_ADDRESS;
-      uint8_t slaveID = (msg & 0x0F0) >> 4;
-      slaveID = slave_CAN_id_to_slave_index[slaveID];
-      uint8_t messageID = msg & 0x00F;
-      updateSlaveInfo(slaveID, messageID, rxFrame);
-    } else if (rxFrame.FrameID == SLAVE_EMERGENCY_ADDRESS) {
-      uint8_t slave_id = rxFrame.data[0];
-      slaves[slave_id].error = 1;
-      memcpy(slaves[slave_id].error_frame, rxFrame.data, 8);
+    switch (rxFrame->FrameID) {
+    case CAN_ID_SLAVE_EMERGENCY:
+      CAN_HandleSlaveEmergency(rxFrame);
+      break;
+    default:
+      if ((rxFrame->FrameID & CAN_MASK_SLAVE_STATUS) ==
+          CAN_ID_SLAVE_STATUS_BASE) {
+        CAN_HandleSlaveStatus(rxFrame);
+      } else if ((rxFrame->FrameID & CAN_MASK_SHUNT) == CAN_ID_SHUNT_BASE) {
+        CAN_HandleShuntMsg(rxFrame);
+      }
+      break;
     }
   }
 
@@ -96,6 +100,23 @@ uint8_t CAN_Transmit(FDCAN_HandleTypeDef* hcan, uint16_t frameid,
 
   return 0;
 }
+
+void CAN_SendAbxStatus(FDCAN_HandleTypeDef* hcan) {
+  uint8_t buffer[4];
+  buffer[0] = airstate.currentTSState | (1 << 7);
+  buffer[1] = current_soc;
+  buffer[2] = (uint8_t)(min_voltage >> 8);
+  buffer[3] = (int8_t)(max_temp >> 4);
+  CAN_Transmit(hcan, CAN_ID_AMS_STATUS, buffer, 4);
+}
+
+void CAN_SendAMSPanic(FDCAN_HandleTypeDef* hcan, AMSErrorHandle* error) {
+  uint8_t buffer[8];
+  buffer[0] = error->errorcode;
+  memcpy(&buffer[1], error->errorarg, 7);
+  CAN_Transmit(hcan, CAN_ID_AMS_PANIC, buffer, 8);
+}
+
 void HAL_FDCAN_ErrorCallback(FDCAN_HandleTypeDef* hcan) {}
 
 void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef* handle,
@@ -136,75 +157,139 @@ void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef* handle,
   framebuffer[framebufferwritepointer].timestamp = HAL_GetTick();
 }
 
-void updateSlaveInfo(uint8_t slaveID, uint8_t MessageID, canFrame rxFrame) {
-  if (slaveID < NUMBEROFSLAVES) {
-    switch (MessageID) {
+void CAN_HandleSlaveStatus(canFrame* rxFrame) {
+  uint16_t msg = rxFrame->FrameID - CAN_ID_SLAVE_STATUS_BASE;
+  uint8_t slaveID = (msg & 0x0F0) >> 4;
+  slaveID = slave_CAN_id_to_slave_index[slaveID];
+  uint8_t messageID = msg & 0x00F;
+
+  if (slaveID < N_SLAVES) {
+    switch (messageID) {
     case 0x00:
-      slaves[slaveID].cellVoltages[0] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellVoltages[1] = rxFrame.data[2] | rxFrame.data[3] << 8;
-      slaves[slaveID].cellVoltages[2] = rxFrame.data[4] | rxFrame.data[5] << 8;
-      slaves[slaveID].cellVoltages[3] = rxFrame.data[6] | rxFrame.data[7] << 8;
+      slaves[slaveID].cellVoltages[0] = rxFrame->data[0] | rxFrame->data[1]
+                                                               << 8;
+      slaves[slaveID].cellVoltages[1] = rxFrame->data[2] | rxFrame->data[3]
+                                                               << 8;
+      slaves[slaveID].cellVoltages[2] = rxFrame->data[4] | rxFrame->data[5]
+                                                               << 8;
+      slaves[slaveID].cellVoltages[3] = rxFrame->data[6] | rxFrame->data[7]
+                                                               << 8;
       break;
     case 0x01:
-      slaves[slaveID].cellVoltages[4] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellVoltages[5] = rxFrame.data[2] | rxFrame.data[3] << 8;
-      slaves[slaveID].cellVoltages[6] = rxFrame.data[4] | rxFrame.data[5] << 8;
-      slaves[slaveID].cellVoltages[7] = rxFrame.data[6] | rxFrame.data[7] << 8;
+      slaves[slaveID].cellVoltages[4] = rxFrame->data[0] | rxFrame->data[1]
+                                                               << 8;
+      slaves[slaveID].cellVoltages[5] = rxFrame->data[2] | rxFrame->data[3]
+                                                               << 8;
+      slaves[slaveID].cellVoltages[6] = rxFrame->data[4] | rxFrame->data[5]
+                                                               << 8;
+      slaves[slaveID].cellVoltages[7] = rxFrame->data[6] | rxFrame->data[7]
+                                                               << 8;
       break;
     case 0x02:
-      slaves[slaveID].cellVoltages[8] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellVoltages[9] = rxFrame.data[2] | rxFrame.data[3] << 8;
+      slaves[slaveID].cellVoltages[8] = rxFrame->data[0] | rxFrame->data[1]
+                                                               << 8;
+      slaves[slaveID].cellVoltages[9] = rxFrame->data[2] | rxFrame->data[3]
+                                                               << 8;
       break;
     case 0x03:
-      slaves[slaveID].cellTemps[0] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellTemps[1] = rxFrame.data[2] | rxFrame.data[3] << 8;
-      slaves[slaveID].cellTemps[2] = rxFrame.data[4] | rxFrame.data[5] << 8;
-      slaves[slaveID].cellTemps[3] = rxFrame.data[6] | rxFrame.data[7] << 8;
+      slaves[slaveID].cellTemps[0] = rxFrame->data[0] | rxFrame->data[1] << 8;
+      slaves[slaveID].cellTemps[1] = rxFrame->data[2] | rxFrame->data[3] << 8;
+      slaves[slaveID].cellTemps[2] = rxFrame->data[4] | rxFrame->data[5] << 8;
+      slaves[slaveID].cellTemps[3] = rxFrame->data[6] | rxFrame->data[7] << 8;
       break;
     case 0x04:
-      slaves[slaveID].cellTemps[4] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellTemps[5] = rxFrame.data[2] | rxFrame.data[3] << 8;
-      slaves[slaveID].cellTemps[6] = rxFrame.data[4] | rxFrame.data[5] << 8;
-      slaves[slaveID].cellTemps[7] = rxFrame.data[6] | rxFrame.data[7] << 8;
+      slaves[slaveID].cellTemps[4] = rxFrame->data[0] | rxFrame->data[1] << 8;
+      slaves[slaveID].cellTemps[5] = rxFrame->data[2] | rxFrame->data[3] << 8;
+      slaves[slaveID].cellTemps[6] = rxFrame->data[4] | rxFrame->data[5] << 8;
+      slaves[slaveID].cellTemps[7] = rxFrame->data[6] | rxFrame->data[7] << 8;
       break;
     case 0x05:
-      slaves[slaveID].cellTemps[8] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellTemps[9] = rxFrame.data[2] | rxFrame.data[3] << 8;
-      slaves[slaveID].cellTemps[10] = rxFrame.data[4] | rxFrame.data[5] << 8;
-      slaves[slaveID].cellTemps[11] = rxFrame.data[6] | rxFrame.data[7] << 8;
+      slaves[slaveID].cellTemps[8] = rxFrame->data[0] | rxFrame->data[1] << 8;
+      slaves[slaveID].cellTemps[9] = rxFrame->data[2] | rxFrame->data[3] << 8;
+      slaves[slaveID].cellTemps[10] = rxFrame->data[4] | rxFrame->data[5] << 8;
+      slaves[slaveID].cellTemps[11] = rxFrame->data[6] | rxFrame->data[7] << 8;
       break;
     case 0x06:
-      slaves[slaveID].cellTemps[12] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellTemps[13] = rxFrame.data[2] | rxFrame.data[3] << 8;
-      slaves[slaveID].cellTemps[14] = rxFrame.data[4] | rxFrame.data[5] << 8;
-      slaves[slaveID].cellTemps[15] = rxFrame.data[6] | rxFrame.data[7] << 8;
+      slaves[slaveID].cellTemps[12] = rxFrame->data[0] | rxFrame->data[1] << 8;
+      slaves[slaveID].cellTemps[13] = rxFrame->data[2] | rxFrame->data[3] << 8;
+      slaves[slaveID].cellTemps[14] = rxFrame->data[4] | rxFrame->data[5] << 8;
+      slaves[slaveID].cellTemps[15] = rxFrame->data[6] | rxFrame->data[7] << 8;
       break;
     case 0x07:
-      slaves[slaveID].cellTemps[16] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellTemps[17] = rxFrame.data[2] | rxFrame.data[3] << 8;
-      slaves[slaveID].cellTemps[18] = rxFrame.data[4] | rxFrame.data[5] << 8;
-      slaves[slaveID].cellTemps[19] = rxFrame.data[6] | rxFrame.data[7] << 8;
+      slaves[slaveID].cellTemps[16] = rxFrame->data[0] | rxFrame->data[1] << 8;
+      slaves[slaveID].cellTemps[17] = rxFrame->data[2] | rxFrame->data[3] << 8;
+      slaves[slaveID].cellTemps[18] = rxFrame->data[4] | rxFrame->data[5] << 8;
+      slaves[slaveID].cellTemps[19] = rxFrame->data[6] | rxFrame->data[7] << 8;
       break;
     case 0x08:
-      slaves[slaveID].cellTemps[20] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellTemps[21] = rxFrame.data[2] | rxFrame.data[3] << 8;
-      slaves[slaveID].cellTemps[22] = rxFrame.data[4] | rxFrame.data[5] << 8;
-      slaves[slaveID].cellTemps[23] = rxFrame.data[6] | rxFrame.data[7] << 8;
+      slaves[slaveID].cellTemps[20] = rxFrame->data[0] | rxFrame->data[1] << 8;
+      slaves[slaveID].cellTemps[21] = rxFrame->data[2] | rxFrame->data[3] << 8;
+      slaves[slaveID].cellTemps[22] = rxFrame->data[4] | rxFrame->data[5] << 8;
+      slaves[slaveID].cellTemps[23] = rxFrame->data[6] | rxFrame->data[7] << 8;
       break;
     case 0x09:
-      slaves[slaveID].cellTemps[24] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellTemps[25] = rxFrame.data[2] | rxFrame.data[3] << 8;
-      slaves[slaveID].cellTemps[26] = rxFrame.data[4] | rxFrame.data[5] << 8;
-      slaves[slaveID].cellTemps[27] = rxFrame.data[6] | rxFrame.data[7] << 8;
+      slaves[slaveID].cellTemps[24] = rxFrame->data[0] | rxFrame->data[1] << 8;
+      slaves[slaveID].cellTemps[25] = rxFrame->data[2] | rxFrame->data[3] << 8;
+      slaves[slaveID].cellTemps[26] = rxFrame->data[4] | rxFrame->data[5] << 8;
+      slaves[slaveID].cellTemps[27] = rxFrame->data[6] | rxFrame->data[7] << 8;
       break;
     case 0x0A:
-      slaves[slaveID].cellTemps[28] = rxFrame.data[0] | rxFrame.data[1] << 8;
-      slaves[slaveID].cellTemps[29] = rxFrame.data[2] | rxFrame.data[3] << 8;
-      slaves[slaveID].cellTemps[30] = rxFrame.data[4] | rxFrame.data[5] << 8;
-      slaves[slaveID].cellTemps[31] = rxFrame.data[6] | rxFrame.data[7] << 8;
+      slaves[slaveID].cellTemps[28] = rxFrame->data[0] | rxFrame->data[1] << 8;
+      slaves[slaveID].cellTemps[29] = rxFrame->data[2] | rxFrame->data[3] << 8;
+      slaves[slaveID].cellTemps[30] = rxFrame->data[4] | rxFrame->data[5] << 8;
+      slaves[slaveID].cellTemps[31] = rxFrame->data[6] | rxFrame->data[7] << 8;
       break;
     }
-    slaves[slaveID].timestamp = rxFrame.timestamp;
-    slaves[slaveID].frame_timestamps[MessageID] = rxFrame.timestamp;
+    slaves[slaveID].timestamp = rxFrame->timestamp;
+    slaves[slaveID].frame_timestamps[messageID] = rxFrame->timestamp;
   }
 }
+
+void CAN_HandleSlaveEmergency(canFrame* rxFrame) {
+  uint8_t slave_id = rxFrame->data[0];
+  slaves[slave_id].error = 1;
+  memcpy(slaves[slave_id].error_frame, rxFrame->data, 8);
+}
+
+void CAN_HandleShuntMsg(canFrame* rxFrame) {
+  switch (rxFrame->FrameID) {
+  case CAN_ID_SHUNT_CURRENT:
+    shunt_data.current = (rxFrame->data[2] << 24) | (rxFrame->data[3] << 16) |
+                         (rxFrame->data[4] << 8) | (rxFrame->data[5]);
+    airstate.shuntCurrent = shunt_data.current;
+    break;
+  case CAN_ID_SHUNT_VOLTAGE_1:
+    shunt_data.voltage1 = (rxFrame->data[2] << 24) | (rxFrame->data[3] << 16) |
+                          (rxFrame->data[4] << 8) | (rxFrame->data[5]);
+    break;
+  case CAN_ID_SHUNT_VOLTAGE_2:
+    shunt_data.voltage2 = (rxFrame->data[2] << 24) | (rxFrame->data[3] << 16) |
+                          (rxFrame->data[4] << 8) | (rxFrame->data[5]);
+    airstate.BatteryVoltageVehicleSide = shunt_data.voltage2;
+    break;
+  case CAN_ID_SHUNT_VOLTAGE_3:
+    shunt_data.voltage3 = (rxFrame->data[2] << 24) | (rxFrame->data[3] << 16) |
+                          (rxFrame->data[4] << 8) | (rxFrame->data[5]);
+    airstate.BatteryVoltageBatterySide = shunt_data.voltage3;
+    break;
+  case CAN_ID_SHUNT_BUSBAR_TEMP:
+    shunt_data.busbartemp = (rxFrame->data[2] << 24) |
+                            (rxFrame->data[3] << 16) | (rxFrame->data[4] << 8) |
+                            (rxFrame->data[5]);
+    break;
+  case CAN_ID_SHUNT_POWER:
+    shunt_data.power = (rxFrame->data[2] << 24) | (rxFrame->data[3] << 16) |
+                       (rxFrame->data[4] << 8) | (rxFrame->data[5]);
+    break;
+  case CAN_ID_SHUNT_ENERGY:
+    shunt_data.energy = (rxFrame->data[2] << 24) | (rxFrame->data[3] << 16) |
+                        (rxFrame->data[4] << 8) | (rxFrame->data[5]);
+    break;
+  case CAN_ID_SHUNT_AMPERE_SECONDS:
+    shunt_data.ampere_seconds = (rxFrame->data[2] << 24) |
+                                (rxFrame->data[3] << 16) |
+                                (rxFrame->data[4] << 8) | (rxFrame->data[5]);
+    break;
+  }
+  shunt_data.last_message = framebuffer[framebufferreadpointer].timestamp;
+}
diff --git a/Core/Src/Check_Shunt_Limits.c b/Core/Src/Check_Shunt_Limits.c
new file mode 100644
index 0000000..1b7754e
--- /dev/null
+++ b/Core/Src/Check_Shunt_Limits.c
@@ -0,0 +1,30 @@
+/*
+ * Check_Shunt_Limits.c
+ *
+ *  Created on: Jun 16, 2022
+ *      Author: max
+ */
+
+#include "Check_Shunt_Limits.h"
+
+#include "AMS_Errorcodes.h"
+#include "main.h"
+
+ShuntData shunt_data;
+
+void CheckShuntLimits() {
+  uint32_t now = HAL_GetTick();
+  if (((shunt_data.last_message + SHUNT_TIMEOUT) < now) && (now > 2000)) {
+    AMSErrorHandle error;
+    error.errorcode = AMS_ERROR_SHUNT_TIMEOUT;
+    AMS_Error_Handler(&error);
+  }
+  /*if(shuntcurrent > SHUNT_OVERCURRENT)
+  {
+          AMS_Error_Handler(0x07);
+  }
+  if(shuntbusbartemp > SHUNT_OVERTEMP)
+  {
+          AMS_Error_Handler(0x08);
+  }*/
+}
diff --git a/Core/Src/Clock_Sync.c b/Core/Src/Clock_Sync.c
index 78f4067..82cf85b 100644
--- a/Core/Src/Clock_Sync.c
+++ b/Core/Src/Clock_Sync.c
@@ -27,9 +27,9 @@ void clock_sync_init(FDCAN_HandleTypeDef* can_handle,
 
 void clock_sync_handle_timer_complete(TIM_HandleTypeDef* timer) {
   if (timer == sync_timer) {
-    CAN_Transmit(can, CLOCK_SYNC_ADDRESS, &clock_sync_counter, 1);
+    CAN_Transmit(can, CAN_ID_CLOCK_SYNC, &clock_sync_counter, 1);
     clock_sync_counter++;
   } else if (timer == heartbeat_timer) {
-    CAN_Transmit(can, MASTER_HEARTBEAT_ADDRESS, NULL, 0);
+    CAN_Transmit(can, CAN_ID_MASTER_HEARTBEAT, NULL, 0);
   }
 }
diff --git a/Core/Src/Fan_Control.c b/Core/Src/Fan_Control.c
new file mode 100644
index 0000000..a70ed4b
--- /dev/null
+++ b/Core/Src/Fan_Control.c
@@ -0,0 +1,25 @@
+/*
+ * Fan_Control.c
+ *
+ *  Created on: Jun 23, 2022
+ *      Author: max
+ */
+
+#include "Fan_Control.h"
+
+#include "stm32g4xx_hal_tim.h"
+
+#include <stdint.h>
+
+TIM_HandleTypeDef* fan_pwm_timer;
+uint32_t fan_pwm_channel;
+
+void Temp_Ctrl_Init(TIM_HandleTypeDef* htim, uint32_t channel) {
+  fan_pwm_timer = htim;
+  fan_pwm_channel = channel;
+  HAL_TIM_PWM_Start(fan_pwm_timer, fan_pwm_channel);
+}
+
+void Temp_Ctrl_Loop() {
+  __HAL_TIM_SET_COMPARE(fan_pwm_timer, fan_pwm_channel, 65000);
+}
diff --git a/Core/Src/Slave_Monitoring.c b/Core/Src/Slave_Monitoring.c
index 74fd075..1ae9729 100644
--- a/Core/Src/Slave_Monitoring.c
+++ b/Core/Src/Slave_Monitoring.c
@@ -13,15 +13,18 @@
 #include "stm32g4xx_hal.h"
 #include "stm32g4xx_hal_gpio.h"
 
+#include <stdint.h>
 #include <string.h>
 
-SlaveHandler slaves[NUMBEROFSLAVES];
+SlaveHandler slaves[N_SLAVES];
+uint16_t min_voltage, max_voltage;
+int16_t min_temp, max_temp;
 
 void initSlaves() {
   HAL_GPIO_WritePin(SLAVES_ENABLE_GPIO_Port, SLAVES_ENABLE_Pin, GPIO_PIN_RESET);
   HAL_GPIO_WritePin(BOOT0_FF_DATA_GPIO_Port, BOOT0_FF_DATA_Pin, GPIO_PIN_RESET);
 
-  for (int i = 0; i < NUMBEROFSLAVES + 5; i++) {
+  for (int i = 0; i < N_SLAVES + 5; i++) {
     HAL_GPIO_WritePin(BOOT0_FF_CLK_GPIO_Port, BOOT0_FF_CLK_Pin, GPIO_PIN_SET);
     HAL_Delay(1);
     HAL_GPIO_WritePin(BOOT0_FF_CLK_GPIO_Port, BOOT0_FF_CLK_Pin, GPIO_PIN_RESET);
@@ -31,11 +34,11 @@ void initSlaves() {
   HAL_Delay(5);
   HAL_GPIO_WritePin(SLAVES_ENABLE_GPIO_Port, SLAVES_ENABLE_Pin, GPIO_PIN_SET);
 
-  for (int n = 0; n < NUMBEROFSLAVES; n++) {
-    for (int i = 0; i < NUMBEROFTEMPS; i++)
+  for (int n = 0; n < N_SLAVES; n++) {
+    for (int i = 0; i < N_TEMP_SENSORS; i++)
       slaves[n].cellTemps[i] = 0;
 
-    for (int j = 0; j < NUMBEROFCELLS; j++)
+    for (int j = 0; j < N_CELLS_SERIES; j++)
       slaves[n].cellVoltages[j] = 32768;
 
     slaves[n].error = 0;
@@ -48,17 +51,21 @@ void initSlaves() {
   }
 }
 
-uint8_t checkSlaveTimeout() {
+uint8_t checkSlaves() {
   if (HAL_GetTick() < 10000) {
     return 0;
   }
 
-  for (int n = 0; n < NUMBEROFSLAVES; n++) {
+  min_voltage = UINT16_MAX;
+  max_voltage = 0;
+  min_temp = INT16_MAX;
+  max_temp = INT16_MIN;
+  for (int n = 0; n < N_SLAVES; n++) {
     if (((int)(HAL_GetTick() - slaves[n].timestamp)) > SLAVETIMEOUT) {
       slaves[n].timeout = 1;
 
       AMSErrorHandle timeouterror;
-      timeouterror.errorcode = SlavesTimeoutError;
+      timeouterror.errorcode = AMS_ERROR_SLAVE_TIMEOUT;
       timeouterror.errorarg[0] = n;
 
       AMS_Error_Handler(&timeouterror);
@@ -67,7 +74,7 @@ uint8_t checkSlaveTimeout() {
 
     if (slaves[n].error) {
       AMSErrorHandle errorframe;
-      errorframe.errorcode = SlavesErrorFrameError;
+      errorframe.errorcode = AMS_ERROR_SLAVE_PANIC;
       memcpy(errorframe.errorarg, slaves[n].error_frame, 7);
       AMS_Error_Handler(&errorframe);
       return 1;
@@ -78,7 +85,7 @@ uint8_t checkSlaveTimeout() {
           SLAVETIMEOUT * 2) {
         slaves[n].timeout = 1;
         AMSErrorHandle timeouterror;
-        timeouterror.errorcode = SLAVES_FRAME_TIMEOUT_ERROR;
+        timeouterror.errorcode = AMS_ERROR_SLAVE_FRAME_TIMEOUT;
         timeouterror.errorarg[0] = n;
         timeouterror.errorarg[1] = i;
         AMS_Error_Handler(&timeouterror);
@@ -86,19 +93,58 @@ uint8_t checkSlaveTimeout() {
       }
     }
 
+    for (int i = 0; i < N_CELLS_SERIES; i++) {
+      uint16_t v = slaves[n].cellVoltages[i];
+      if (v > max_voltage) {
+        max_voltage = v;
+      }
+      if (v < min_voltage) {
+        min_voltage = v;
+      }
+    }
+
     int working_cell_temps = 0;
-    for (int i = 0; i < NUMBEROFTEMPS; i++) {
-      if (slaves[n].cellTemps[i] != 0) {
+    for (int i = 0; i < N_TEMP_SENSORS; i++) {
+      int16_t t = slaves[n].cellTemps[i];
+      if (t != 0) {
         working_cell_temps++;
+        if (t > max_temp) {
+          max_temp = t;
+        }
+        if (t < min_temp) {
+          min_temp = t;
+        }
       }
     }
     if (working_cell_temps < SLAVE_MIN_TEMP_SENSORS) {
       AMSErrorHandle temperror;
-      temperror.errorcode = SLAVES_TOO_FEW_TEMPS;
+      temperror.errorcode = AMS_ERROR_SLAVE_TOO_FEW_TEMPS;
       temperror.errorarg[0] = n;
       AMS_Error_Handler(&temperror);
       return 1;
     }
   }
+
+  AMSErrorHandle thresherror;
+  thresherror.errorcode = AMS_ERROR_MASTER_THRESH;
+  int error = 0;
+  if (min_temp < THRESH_UT) {
+    error = 1;
+    thresherror.errorarg[0] = AMS_ERRORARG_MASTER_THRESH_UT;
+  } else if (max_temp > THRESH_OT) {
+    error = 1;
+    thresherror.errorarg[0] = AMS_ERRORARG_MASTER_THRESH_OT;
+  } else if (min_voltage < THRESH_UV) {
+    error = 1;
+    thresherror.errorarg[0] = AMS_ERRORARG_MASTER_THRESH_UV;
+  } else if (max_voltage > THRESH_OV) {
+    error = 1;
+    thresherror.errorarg[0] = AMS_ERRORARG_MASTER_THRESH_OV;
+  }
+
+  if (error) {
+    AMS_Error_Handler(&thresherror);
+  }
+
   return 0;
 }
diff --git a/Core/Src/SoC_Estimation.c b/Core/Src/SoC_Estimation.c
new file mode 100644
index 0000000..4c77c93
--- /dev/null
+++ b/Core/Src/SoC_Estimation.c
@@ -0,0 +1,70 @@
+#include "SoC_Estimation.h"
+
+#include "CAN_Communication.h"
+#include "Check_Shunt_Limits.h"
+#include "util.h"
+
+#include <stdint.h>
+
+uint8_t current_soc = 0;
+
+static const float internal_resistance_curve_x[] = {2.0, 4.12};
+static const float internal_resistance_curve_y[] = {0.0528, 0.0294};
+#define INTERNAL_RESISTANCE_CURVE_PTS                                          \
+  (sizeof(internal_resistance_curve_x) / sizeof(*internal_resistance_curve_x))
+static const float soc_ocv_x[] = {2.1, 2.9,  3.2, 3.3,  3.4,
+                                  3.5, 3.68, 4.0, 4.15, 4.2};
+static const float soc_ocv_y[] = {0,     0.023, 0.06,  0.08,  0.119,
+                                  0.227, 0.541, 0.856, 0.985, 1.0};
+#define SOC_OCV_PTS (sizeof(soc_ocv_x) / sizeof(*soc_ocv_x))
+
+static int start_soc_known = 0;
+static float start_soc;
+static float start_as;
+static float min_cell_voltage;
+
+static void estimate_start_soc_off();
+static void estimate_start_soc_on();
+
+void estimate_soc() {
+  uint16_t min_v = 0xFFFF;
+  for (int slave = 0; slave < N_SLAVES; slave++) {
+    for (int cell = 0; cell < N_CELLS_SERIES; cell++) {
+      uint16_t v = slaves[slave].cellVoltages[cell];
+      if (v < min_v) {
+        min_v = v;
+      }
+    }
+  }
+  min_cell_voltage = min_v * CELL_VOLTAGE_CONVERSION_FACTOR;
+
+  if (shunt_data.current < SOCE_SHUNT_CURRENT_OFF_THRESH) {
+    estimate_start_soc_off();
+  } else if (!start_soc_known) {
+    estimate_start_soc_on();
+  }
+
+  float soc =
+      start_soc - (shunt_data.ampere_seconds - start_as) / BATTERY_CAPACITY;
+  current_soc = soc * 255;
+}
+
+static void estimate_start_soc_on() {
+  float r_i = interp(INTERNAL_RESISTANCE_CURVE_PTS, internal_resistance_curve_x,
+                     internal_resistance_curve_y, min_cell_voltage);
+  float i = ((float)shunt_data.current) / N_CELLS_PARALLEL;
+  float ocv = min_cell_voltage - i * r_i;
+  start_soc = calculate_soc_for_ocv(ocv);
+  start_as = shunt_data.ampere_seconds;
+  start_soc_known = 1;
+}
+
+static void estimate_start_soc_off() {
+  start_soc = calculate_soc_for_ocv(min_cell_voltage);
+  start_as = shunt_data.ampere_seconds;
+  start_soc_known = 1;
+}
+
+float calculate_soc_for_ocv(float ocv) {
+  return interp(SOC_OCV_PTS, soc_ocv_x, soc_ocv_y, ocv);
+}
diff --git a/Core/Src/main.c b/Core/Src/main.c
index 10e62b7..5282451 100644
--- a/Core/Src/main.c
+++ b/Core/Src/main.c
@@ -23,9 +23,15 @@
 /* USER CODE BEGIN Includes */
 #include "AIR_State_Maschine.h"
 #include "CAN_Communication.h"
+#include "Check_Shunt_Limits.h"
 #include "Clock_Sync.h"
 #include "Error_Check.h"
+#include "Fan_Control.h"
 #include "Slave_Monitoring.h"
+#include "SoC_Estimation.h"
+
+#include "stm32g4xx_hal.h"
+#include "stm32g4xx_hal_tim.h"
 /* USER CODE END Includes */
 
 /* Private typedef -----------------------------------------------------------*/
@@ -66,7 +72,6 @@ void setAMSError(void);
 
 /* Private user code ---------------------------------------------------------*/
 /* USER CODE BEGIN 0 */
-AIRStateHandler airstates;
 ErrorFlags errorflags;
 AMSErrorHandle defaulterrorhandle = {0};
 /* USER CODE END 0 */
@@ -104,10 +109,11 @@ int main(void) {
   MX_TIM1_Init();
   MX_TIM8_Init();
   /* USER CODE BEGIN 2 */
-  airstates = init_AIR_State_Maschine();
+  init_AIR_State_Maschine();
   CAN_Init(&hfdcan1);
   clock_sync_init(&hfdcan1, &htim1, &htim8);
   initSlaves();
+  Temp_Ctrl_Init(&htim3, TIM_CHANNEL_4);
   /* USER CODE END 2 */
 
   /* Infinite loop */
@@ -116,11 +122,21 @@ int main(void) {
     /* USER CODE END WHILE */
 
     /* USER CODE BEGIN 3 */
-    CAN_Receive(&hfdcan1);          // Run CAN Event Loop
-    errorflags = CheckErrorFlags(); // Check for Errors
-    Update_AIR_Info(&airstates);
-    checkSlaveTimeout();          // check for Slave Timeout
-    Update_AIR_State(&airstates); // Update AIR State Maschine
+    HAL_GPIO_TogglePin(STATUS_LED_GPIO_Port, STATUS_LED_Pin);
+
+    CAN_Receive(&hfdcan1);
+
+    errorflags = CheckErrorFlags();
+    checkSlaves();
+    CheckShuntLimits();
+
+    Update_AIR_State();
+
+    estimate_soc();
+    CAN_SendAbxStatus(&hfdcan1);
+    Temp_Ctrl_Loop();
+
+    HAL_Delay(10);
   }
   /* USER CODE END 3 */
 }
@@ -389,10 +405,11 @@ static void MX_GPIO_Init(void) {
 void AMS_Error_Handler(AMSErrorHandle* errorinfo) {
   while (1) {
     setAMSError();
-    airstates.targetTSState = TS_ERROR;
-    Update_AIR_State(&airstates);
+    airstate.targetTSState = TS_ERROR;
+    Update_AIR_State();
     CAN_Receive(&hfdcan1);
     errorflags = CheckErrorFlags();
+    CAN_SendAMSPanic(&hfdcan1, errorinfo);
   }
 }
 
diff --git a/Core/Src/util.c b/Core/Src/util.c
new file mode 100644
index 0000000..919096e
--- /dev/null
+++ b/Core/Src/util.c
@@ -0,0 +1,27 @@
+#include "util.h"
+
+#include <stdint.h>
+
+float interp(uint32_t n_points, const float* source_x, const float* source_y,
+             float target_x) {
+  uint32_t i;
+  for (i = 0; i < n_points; i++) {
+    if (source_x[i] > target_x) {
+      break;
+    }
+  }
+  if (i == 0) {
+    // target_x is smaller than the smallest value in source_x
+    i++;
+  }
+  if (i == n_points) {
+    // target_y is larger than the largest value in source_x
+    i--;
+  }
+  float x1 = source_x[i - 1];
+  float x2 = source_x[i];
+  float y1 = source_y[i - 1];
+  float y2 = source_y[i];
+  float slope = (y2 - y1) / (x2 - x1);
+  return y1 + slope * (target_x - x1);
+}
diff --git a/STM32Make.make b/STM32Make.make
index 6b7fb02..33fc1d4 100644
--- a/STM32Make.make
+++ b/STM32Make.make
@@ -38,13 +38,17 @@ BUILD_DIR = build
 C_SOURCES =  \
 Core/Src/AIR_State_Maschine.c \
 Core/Src/CAN_Communication.c \
+Core/Src/Check_Shunt_Limits.c \
 Core/Src/Clock_Sync.c \
 Core/Src/Error_Check.c \
+Core/Src/Fan_Control.c \
 Core/Src/Slave_Monitoring.c \
+Core/Src/SoC_Estimation.c \
 Core/Src/main.c \
 Core/Src/stm32g4xx_hal_msp.c \
 Core/Src/stm32g4xx_it.c \
 Core/Src/system_stm32g4xx.c \
+Core/Src/util.c \
 Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal.c \
 Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_cortex.c \
 Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma.c \