浏览代码

updated the peripherals to a separate folder

namrota ghosh 8 月之前
当前提交
db8623923e

+ 68 - 0
src/peripherals/adc/adc.c

@@ -0,0 +1,68 @@
+#include "src/battery.h"
+#include "src/interfaces/i2c_controller_interface.h"
+#include "ti/driverlib/dl_i2c.h"
+#include "ti/driverlib/m0p/dl_core.h"
+#include "ti_msp_dl_config.h"
+#include "src/peripherals/adc/adc.h"
+#include <stdint.h>
+#include <stdio.h>
+#include "src/peripherals/adc/adc_interface.h"
+
+
+static ADC_Params adc_params;
+static ADC_MeasurementState adc_state = ADC_STATE_CONFIGURE;
+
+
+void updateADCReading_multichannel(uint8_t slot, uint8_t channel) {
+  
+  while (adc_state != ADC_STATE_DONE) {
+    switch (adc_state) {
+
+    case ADC_STATE_CONFIGURE:
+      adc_params.channel = channel;
+      //printf("Channel: %d\n", adc_params.channel);
+      adc_params.resolution = 12;
+      adc_params.continuous = 0;
+      adc_params.gain = 1;
+      adc_hal.configure(slot, adc_params);
+      //ADC_SetConfigurationBytes(adc_params);
+      adc_state = ADC_STATE_WAIT;
+      break;
+
+    case ADC_STATE_WAIT:
+      //if (ADC_CheckReadyBit(slot, adc_params)) {
+      if(adc_hal.is_ready(slot, adc_params)){
+        adc_state = ADC_STATE_READ;
+      }
+      break;
+
+    case ADC_STATE_READ:
+      if (channel == 0) {
+
+        int16_t raw_adc_voltage = adc_hal.read_raw(slot, adc_params);
+        batteries[slot].voltage =
+            adc_hal.convert_voltage(raw_adc_voltage, adc_params); 
+        printf("[ADC] Battery voltage for slot %d is %u mV.\n", slot,
+               batteries[slot].voltage);
+        adc_state = ADC_STATE_DONE;
+
+      } else if (channel == 1) {
+
+        int16_t raw_adc_current = adc_hal.read_raw(slot, adc_params);
+        batteries[slot].current =
+            adc_hal.convert_current(raw_adc_current, adc_params);
+        printf("[ADC] Battery current for slot %d is %u mA.\n", slot,
+               batteries[slot].current);
+
+        adc_state = ADC_STATE_DONE;
+      }
+      break;
+    default:
+      channel = 0;
+      adc_state = ADC_STATE_CONFIGURE;
+      break;
+    }
+  }
+
+  adc_state = ADC_STATE_CONFIGURE;
+}

+ 45 - 0
src/peripherals/adc/adc.h

@@ -0,0 +1,45 @@
+
+#ifndef ADC_H_
+#include "ti/driverlib/dl_i2c.h"
+#include "ti_msp_dl_config.h"
+#include "src/battery.h"
+
+
+//Maximum packet sizes
+/*#define I2C_TX_MAX_PACKET_SIZE (16)
+#define I2C_RX_MAX_PACKET_SIZE (16)
+*/
+//Flag for READ and WRITE
+/*extern volatile bool gRxComplete;
+extern volatile bool gTxComplete;
+extern uint8_t gTxPacket[I2C_TX_MAX_PACKET_SIZE];
+extern uint8_t gRxPacket[I2C_RX_MAX_PACKET_SIZE];
+*/
+/*Counters for Tx and Rx length and bytes sent*/
+/*extern uint32_t gTxADClen, gTxADCcount;
+extern uint32_t gRxADClen, gRxADCcount;
+*/
+//ADC states
+typedef enum{
+    ADC_STATE_CONFIGURE,
+    ADC_STATE_WAIT,
+    ADC_STATE_READ,
+    ADC_STATE_DONE
+}ADC_MeasurementState;
+
+/*typedef struct{
+    uint8_t channel;
+    uint8_t resolution;
+    bool continuous;
+    uint8_t gain;
+} ADC_PARAMS;*/
+
+
+//void ADC_SetConfigurationBytes(ADC_PARAMS params);
+//bool ADC_CheckReadyBit(uint8_t slot_id, ADC_PARAMS params);
+//int16_t ADC_ReadData(uint8_t slot_id, ADC_PARAMS params);
+//void Battery_UpdateVoltage(ADC_PARAMS params);
+//void Battery_UpdateCurrent(ADC_PARAMS params);
+void updateADCReading_multichannel(uint8_t slot, uint8_t channel); //belongs to battery module
+//void Battery_ReadState(uint8_t slot_id); //belongs to battery module
+#endif

+ 235 - 0
src/peripherals/adc/adc_hal.c

@@ -0,0 +1,235 @@
+/*
+This adc file will handle:
+- packet configuration: bool
+- adc ready flag: bool
+- adc_read_raw: int_16
+
+Function to read ADC DATA: This function simply retrieves the ADC raw digital
+output as 16-bit signed integer.
+* The value returned is not yet converted to VOLTAGE.
+* adc_data[2]: Buffer with an array of size 2, to store two bytes of ADC data.
+*             Since, the ADC output consists of two 8-bit bytes:
+*             - adc_data[0] (MSB)
+*             - adc_data[1] (LSB)
+* Next, we verify if the the I2C bus is busy using the function in the
+driverlib: DL_I2C_get ControllerStatus
+*       - Prevents collisions by ensuring no two I2C device is using the same
+bus before initializing.
+* BEGIN I2C READ operation to request 2 bytes from the ADC->
+DL_I2C_startControllerTransfer()
+* Parameters:
+    - I2C_controller_INST: Refererence to the I2C instance bring used.
+    - DEF_TARGET_ADDR_ADC: Address of the ADC
+    - DL_I2C_CONTROLLER_DIRECTION_RX: Indicates that we want to receive the data
+from ADC
+    - 2: Specifies that we expect 2 bytes from the ADC
+* WAIT for the data to be received: (DL_I2C_getControllerStatus())
+    - Waits until the ADC sends the data over I2C.
+    - Ensures that the data transfer is complete before proceeding.
+* READ the two bytes of ADc Data:
+    - adc_data[0] : MSB
+    - adc_data[1] : LSB
+    - adc_data[2] : config_bytes
+    ADC sends its 16-bit value in two parts over 8-bit I2C data frames.
+* COMBINE the two bytes into 16-bit Integer:
+    - Shifts the MSB(first byte) left by 8 bits to make space for LSB.
+    - Performs a bitwise OR operation to combine MSB and LSB into a single
+16-bit number.
+* PRINT HEXADEC and DECIMAL format for DEBUGGING.
+* Output code is in binary and is proportional to the Input Voltage and PGA
+settings.
+* From the datasheet:
+https://ww1.microchip.com/downloads/aemDocuments/documents/OTH/ProductDocuments/DataSheets/22226a.pdf
+    - Equation 4.4 is being used to convert the output codes to input voltage
+
+* The ACK bits after conversion is issued by the Master, when the device
+receives a READ command, it outputs two data bytes followed by a configuration
+register in 16 bit conversion mode the MSB(=sign bit) of the first data type is
+D15.
+*/
+
+
+#include "src/interfaces/i2c_controller_interface.h"
+#include "src/peripherals/adc/adc_interface.h"
+#include "ti_msp_dl_config.h"
+#include <stdio.h>
+
+volatile bool gRxComplete;
+volatile bool gTxComplete;
+uint8_t gTxPacket[I2C_TX_MAX_PACKET_SIZE];
+uint8_t gRxPacket[I2C_RX_MAX_PACKET_SIZE];
+uint32_t gTxADClen, gTxADCcount;
+uint32_t gRxADClen, gRxADCcount;
+
+/*
+* Creating Configuartion Register as mentioned in the datasheet: https://ww1.microchip.com/downloads/aemDocuments/documents/OTH/ProductDocuments/DataSheets/22226a.pdf
+* Under section 5.2 Configuration Register
+* The function is private to ADC and is can only be called in this file
+*/
+static uint8_t construct_config_byte(ADC_Params params) {
+
+  uint8_t config = 0;
+
+  config |= ((params.channel) << 5); // Channel Selection (Bits 6-5)
+
+  config |= (1 << 4); // One-Shot Mode
+
+  switch (params.resolution) {
+  case 12:
+    config |= (0b00 << 2);
+    break;
+  case 14:
+    config |= (0b01 << 2);
+    break;
+  case 16:
+    config |= (0b10 << 2);
+    break;
+  default:
+    printf("ERROR: Invalid Resolution!\n");
+    return 0;
+  }
+
+  switch (params.gain) {
+  case 1:
+    config |= (0b00);
+    break;
+  case 2:
+    config |= (0b01);
+    break;
+  case 4:
+    config |= (0b10);
+    break;
+  default:
+    printf("ERROR: Invalid Gain!\n");
+    return 0;
+  }
+
+  return config;
+}
+
+/* Tansmit Data from MCU to ADC:  Function to SET configuration to ADC over
+ * I2C*/
+
+static bool adc_configure(uint8_t slot_id, ADC_Params params) {
+  // **Construct Configuration Byte**
+  uint8_t config_byte = construct_config_byte(params);
+  // Wait for I2C Bus to be Free**
+  while (DL_I2C_getControllerStatus(I2C_controller_INST) &
+         DL_I2C_CONTROLLER_STATUS_BUSY_BUS)
+    ;
+  if(config_byte == 0xFF) return false;
+  // Prepare TX Buffer:
+  gTxPacket[0] = config_byte;
+  gTxADClen = 1;
+  gTxADCcount = 0;
+  gTxComplete = false;
+
+  return i2c_hal.write(ADC_TARGET_BASE_ADDRESS, gTxPacket, gTxADClen);
+  //return i2c_hal.write(ADC_TARGET_BASE_ADDRESS + slot_id, &config_byte, 1);
+}
+
+
+/*
+READY BIT:
+    This bit is the data ready flag. In read mode, this bit indicates if the
+output register has been updated with a latest conversion result. In One-Shot
+Conversion mode, writing this bit to “1” initiates a new conversion.
+
+    1= Output Register has not been updated
+    0= Output Register has been updated
+
+*/
+
+static bool adc_is_ready(uint8_t slot_id, ADC_Params params) {
+  uint8_t adc_address = ADC_TARGET_BASE_ADDRESS + slot_id;
+  gRxADClen = 3;
+  gRxADCcount = 0;
+  gRxComplete = false;
+
+  i2c_hal.read(adc_address, gRxADClen);
+  //printf("Reading ADC Data from MCP3428 for channel: %u\n", params.channel);
+  //i2c_hal.read(ADC_TARGET_BASE_ADDRESS + slot_id, 3);
+  uint8_t config_adc_byte = gRxPacket[2];
+  // Ready bit is bit 7
+  bool ready = (config_adc_byte & 0x80) == 0;
+  return ready;
+}
+
+
+static int16_t read_adc_raw_data(uint8_t slot_id, ADC_Params params) {
+
+  // Buffer for ADC data (MSB, LSB, Config Byte)
+  uint8_t adc_data[3] = {0};
+  int16_t raw_adc = 0;
+  uint8_t bytes_to_read = 3;
+  gRxADClen = bytes_to_read;
+  gRxADCcount = 0;
+  gRxComplete = false;
+  i2c_hal.read(ADC_TARGET_BASE_ADDRESS + slot_id, gRxADClen);
+  uint8_t msb = gRxPacket[0];
+  uint8_t lsb = gRxPacket[1];
+  uint8_t config_adc_byte = gRxPacket[2];
+  //printf("MSB: 0x%02X, LSB: 0x%02X\n", msb, lsb);
+  uint8_t gain_setting = (config_adc_byte & 0x03);
+  uint8_t gain_multiplier = (1 << gain_setting); // Gain values: 1, 2, 4, 8
+  if (params.resolution == 16) {
+    raw_adc = (msb << 8) | lsb;
+    if (raw_adc > 32767)
+      raw_adc -= 65536;
+  } else if (params.resolution == 14) {
+    raw_adc = ((msb & 0b00111111) << 8) | lsb;
+    if (raw_adc > 8191)
+      raw_adc -= 16384;
+  } else if (params.resolution == 12) {
+    raw_adc = ((msb & 0b00001111) << 8) | lsb;
+    if (raw_adc > 2047)
+      raw_adc -= 4096;
+  }
+  //printf("Raw ADC Value: 0x%0X (%d)\n", raw_adc, raw_adc);
+  return raw_adc;
+}
+
+/* Function to Convert ADC Reading to Voltage */
+static uint16_t adc_voltage(int16_t adc_value, ADC_Params params) {
+  uint16_t measured_voltage = 0;
+  uint16_t LSB = 0;
+  uint32_t max_adc_value = 1;
+
+  switch (params.resolution) {
+  case 12: // 12-bit
+    max_adc_value = 4095;
+    break;
+  case 14: // 14-bit
+    max_adc_value = 16383;
+    break;
+  case 16: // 16-bit
+    max_adc_value = 65535;
+    break;
+  default:
+    printf("Error: Unknown ADC Resolution!\n");
+    return 0;
+  }
+  measured_voltage = (((uint32_t)adc_value) * 2.7);
+  return (uint16_t)measured_voltage;
+}
+
+/* Function to Convert ADC Reading to Voltage */
+uint16_t adc_current(int16_t adc_value, ADC_Params params) {
+  int16_t current_mA = 0;
+  // Convert ADC value to voltage across shunt resistor:
+  uint16_t voltage_mV = adc_voltage(adc_value, params);
+  uint8_t gain_multiplier = (1 << (params.gain - 1));
+  // Convert voltage drop across shunt resistor to current
+  current_mA = (adc_value) * (10 * gain_multiplier);
+  // printf("Converted Current: %d mA.\n", current_mA);
+  return (int16_t)current_mA;
+}
+
+
+ADC_Interface adc_hal= {
+    .configure= adc_configure,
+    .read_raw= read_adc_raw_data,
+    .is_ready= adc_is_ready,
+    .convert_voltage= adc_voltage,
+    .convert_current= adc_current
+};

+ 43 - 0
src/peripherals/adc/adc_interface.h

@@ -0,0 +1,43 @@
+#ifndef ADC_INTERFACE_H_
+#define ADC_INTERFACE_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#define ADC_TARGET_BASE_ADDRESS (0x68)
+#define ADC_VREF_MV (2048)
+#define DELAY (100000) //define timeout limit
+#define ADC_CHANNEL_NUM (2)
+//Maximum packet sizes
+#define I2C_TX_MAX_PACKET_SIZE (16)
+#define I2C_RX_MAX_PACKET_SIZE (16)
+
+//Flag for READ and WRITE
+extern volatile bool gRxComplete;
+extern volatile bool gTxComplete;
+extern uint8_t gTxPacket[I2C_TX_MAX_PACKET_SIZE];
+extern uint8_t gRxPacket[I2C_RX_MAX_PACKET_SIZE];
+
+/*Counters for Tx and Rx length and bytes sent*/
+extern uint32_t gTxADClen, gTxADCcount;
+extern uint32_t gRxADClen, gRxADCcount;
+
+typedef struct {
+    uint8_t channel;
+    uint8_t resolution;
+    bool continuous;
+    uint8_t gain;
+} ADC_Params;
+
+
+typedef struct {
+    bool (*configure)(uint8_t slot_id, ADC_Params params);
+    bool (*is_ready)(uint8_t slot_id, ADC_Params params);
+    int16_t (*read_raw)(uint8_t slot_id, ADC_Params params);
+    uint16_t (*convert_voltage)(int16_t raw, ADC_Params params);
+    uint16_t (*convert_current)(int16_t raw, ADC_Params params);
+} ADC_Interface;
+
+extern ADC_Interface adc_hal;
+
+#endif

+ 156 - 0
src/peripherals/dac/dac.c

@@ -0,0 +1,156 @@
+#include "src/peripherals/dac/dac.h"
+#include "src/interfaces/i2c_controller_interface.h"
+#include "ti/driverlib/dl_i2c.h"
+#include "ti_msp_dl_config.h"
+#include <stdint.h>
+#include <stdio.h>
+
+// The device updates all DAC analog output(vout) at the same time
+
+void DAC_UpdateOutput() {
+  uint8_t general_call_command = 0x08; // General Call Update Command
+  while (DL_I2C_getControllerStatus(I2C_controller_INST) &
+         DL_I2C_CONTROLLER_STATUS_BUSY_BUS)
+    ;
+
+  // Start I2C transaction
+  DL_I2C_startControllerTransfer(I2C_controller_INST, 0x00,
+                                 DL_I2C_CONTROLLER_DIRECTION_TX, 1);
+
+  while (DL_I2C_getControllerStatus(I2C_controller_INST) &
+         DL_I2C_CONTROLLER_STATUS_BUSY_BUS)
+    ;
+
+  DL_I2C_fillControllerTXFIFO(I2C_controller_INST, &general_call_command, 1);
+
+  //printf("DAC Outputs Updated via General Call Software Update!\n");
+}
+
+/**Function for FAST write command, sending values over I2c to every channel of
+ * DAC**/
+bool DAC_fastWrite(uint16_t channel_a_value) {
+
+  /*DAC has a 12 bit resolution that ranges from 0 to 4095.
+  0x00: sets the Power Mode to NORMAL for Channel A
+  (channel_a_value >> 8): shifts the value to 8 places right and gives upper 4
+  bits VoutA channel, rest channels are powered down Each Vout pins is driven by
+  its own output buffer with a gain of 1 or 2.
+
+  */
+
+  uint8_t output_buffer[8];
+
+  output_buffer[0] = 0x01;
+  output_buffer[1] = 0x00;
+
+  // Normal Mode: PD0 and PD1 is 00
+  output_buffer[2] = (0x00) | ((channel_a_value >> 8) & 0x0F);
+  output_buffer[3] = channel_a_value & 0xFF;
+
+  output_buffer[4] = 0x01;
+  output_buffer[5] = 0x00;
+
+  output_buffer[6] = 0x01;
+  output_buffer[7] = 0x00;
+
+  if (!DL_I2C_CONTROLLER_STATUS_ADDR_ACK) {
+    printf("DAC Address Failure");
+    return false;
+  }
+
+  i2c_hal.write(DAC_TARGET_BASE_ADDRESS, (uint8_t *)&output_buffer, 8);
+  //printf("Output Buffer[2]: 0x%02X, Output Buffer[3]: 0x%02X\n",
+  //      output_buffer[2], output_buffer[3]);
+  //printf("DAC Fast write Successful!\n");
+  DAC_UpdateOutput();
+  return true;
+}
+
+/*
+LDAC pin is set to HIGH or LOW
+LDAC "HIGH": until the end of the positive pulse of the 8th clock of the 2nd
+byte LDAC "LOW": negative pulse of the 8th clock of the 2nd byte and stays low
+until the rising edge of the 9th clock of the 3rd byte LDAC pin resumes normal
+function after STOP bit Device address of 0x60 till 0x67, default is 0x60
+*/
+
+/*void ldac_pin_init() {
+  // Default set to HIGH
+  DL_GPIO_setPins(LDAC_PIN_PORT, LDAC_PIN_PIN_PA8_PIN);
+}
+
+void set_ldac(bool level) {
+  if (level) {
+    // Set LDAC Pins HIGH
+    DL_GPIO_setPins(LDAC_PIN_PORT, LDAC_PIN_PIN_PA8_PIN);
+  } else {
+    // Set LDAC Pins LOW
+    DL_GPIO_clearPins(LDAC_PIN_PORT, LDAC_PIN_PIN_PA8_PIN);
+  }
+}*/
+
+/*General Call Read Address: Command to read I2C address bits of the device*/
+uint8_t DAC_ReadCurrentAddress() {
+  uint8_t current_address = 0;
+  // General call address bits
+  uint8_t command = 0xC3;
+  while (DL_I2C_getControllerStatus(I2C_controller_INST) &
+         DL_I2C_CONTROLLER_STATUS_BUSY_BUS)
+    ;
+
+  // Send General Call Read Address Command
+  DL_I2C_startControllerTransfer(I2C_controller_INST, I2C_GENERAL_CALL_ADDR,
+                                 DL_I2C_CONTROLLER_DIRECTION_TX, 1);
+  DL_I2C_fillControllerTXFIFO(I2C_controller_INST, &command, 1);
+
+  while (DL_I2C_getControllerStatus(I2C_controller_INST) &
+         DL_I2C_CONTROLLER_STATUS_BUSY_BUS)
+    ;
+
+  // Read the response (Current DAC I2C address)
+  DL_I2C_startControllerTransfer(I2C_controller_INST, I2C_GENERAL_CALL_ADDR,
+                                 DL_I2C_CONTROLLER_DIRECTION_RX, 1);
+  current_address = DL_I2C_receiveControllerData(I2C_controller_INST);
+
+  // Debug
+  //printf("Current DAC I2C Address: 0x%02X\n", current_address);
+  return current_address;
+}
+
+/*
+Single Write for DAC: writes the input data to a selected single DAC input
+register and also to its EEPROM. DAC1: Channel Selection Bits
+    - 00 Channel A
+    - 01 Channel B
+    - 10 Channel C
+    - 11 Channel D
+
+UDAC: DAC latch bit
+    - 0: Upload
+    - 1: Do not upload
+*/
+bool DAC_SingleWrite(uint16_t channel_value) {
+  if(channel_value > 4095){
+    printf("DAC Error: channel_value out of range. Must be between 0 and 4095\n");
+    return false;
+  }
+  uint8_t data_length = 3;
+  uint8_t output_buffer_SingleWrite[data_length];
+  //C2 C1 C0 W1 W0: 01011 | DAC1 DAC0: 00| UDAC:0
+  output_buffer_SingleWrite[0] = 0x5A; //0x58 for Channel 0
+  output_buffer_SingleWrite[1] = (0x10) | ((channel_value >> 8) & 0x0F);
+  output_buffer_SingleWrite[2] = (channel_value & 0xFF);
+
+  // Write data to DAC
+  if (!i2c_hal.write(DAC_TARGET_BASE_ADDRESS, output_buffer_SingleWrite, data_length)) {
+        printf("I2C DAC Write Error: Failed to write to DAC.\n");
+        return false;
+    }
+
+  DAC_UpdateOutput();
+
+  //printf("Output_Buffer_1: 0x%02X, Output_Buffer_2: 0x%02X\n", output_buffer_SingleWrite[1], output_buffer_SingleWrite[2]);
+
+  return true;
+
+}

+ 16 - 0
src/peripherals/dac/dac.h

@@ -0,0 +1,16 @@
+#ifndef DAC_H_
+#include "ti/driverlib/dl_i2c.h"
+#include "ti_msp_dl_config.h"
+#include <stdbool.h>
+
+#define DAC_TARGET_BASE_ADDRESS (0x60)
+//#define CHANNEL_A_VALUE (800) // in mAmps
+#define I2C_GENERAL_CALL_ADDR  0x00
+#define DAC_VREF_MV 2048
+
+bool DAC_fastWrite(uint16_t channel_a_value);
+void DAC_UpdateOutput();
+uint8_t DAC_ReadCurrentAddress();
+bool DAC_SingleWrite(uint16_t channel_value);
+
+#endif

+ 132 - 0
src/peripherals/mux/multiplexer.c

@@ -0,0 +1,132 @@
+#include "src/peripherals/mux/multiplexer.h"
+#include "ti/driverlib/dl_i2c.h"
+#include "ti_msp_dl_config.h"
+#include <stdio.h>
+#include <stdint.h>
+
+/*
+Multiplexer TCA9548A:
+Address:0x70
+The TCA9548A is example of a single-register device, which is controlled via I2C commands. Since it has 1 bit to enable or disable a channel, there is only 1 register
+needed, and the controller merely writes the register data after the target address, skipping the register number.
+ADC connected to channel 0
+Both SDA and SL lines of the multiplexer is connected to VIN through pull-up resistors
+The following is the general procedure for a controller to access a target device:
+1. If a controller wants to send data to a target:
+    • Controller-transmitter sends a START condition and addresses the target-receiver.
+    • Controller-transmitter sends data to target-receiver.
+    • Controller-transmitter terminates the transfer with a STOP condition.
+2. If a controller wants to receive or read data from a target:
+    • Controller-receiver sends a START condition and addresses the target-transmitter.
+    • Controller-receiver sends the requested register to read to target-transmitter.
+    • Controller-receiver receives data from the target-transmitter.
+    • Controller-receiver terminates the transfer with a STOP condition.
+The TCA9548A is example of a single-register device, which is controlled via I2C commands. Since it has 1 bit to enable or disable a channel, 
+there is only 1 register needed, and the controller merely writes the register data after the target address, skipping the register number.
+*/
+
+/*
+Scans all the addresses of the peripherals:
+*/
+void I2C_scanBus() {
+    printf("Scanning I2C Bus...\n");
+
+    // **Step 1: Reset I2C Controller if Busy**
+    if (DL_I2C_getControllerStatus(I2C_controller_INST) & DL_I2C_CONTROLLER_STATUS_BUSY_BUS) {
+        printf("I2C Bus Busy! Resetting I2C Controller...\n");
+        DL_I2C_disableController(I2C_controller_INST);  // Disable I2C
+        delay_cycles(20000);
+        DL_I2C_enableController(I2C_controller_INST);   // Re-enable I2C
+        delay_cycles(20000);
+    }
+
+    // **Step 2: Scan I2C Bus**
+    for (uint8_t addr = 0x08; addr < 0x78; addr++) {  // Valid I2C Address Range
+        DL_I2C_startControllerTransfer(I2C_controller_INST, addr, DL_I2C_CONTROLLER_DIRECTION_RX, 1);
+        delay_cycles(5000);
+        
+        if (!(DL_I2C_getControllerStatus(I2C_controller_INST) & DL_I2C_CONTROLLER_STATUS_ERROR)) {
+            printf("Device found at: 0x%02X\n", addr);
+        }else {
+            // Clear the error by resetting the I2C controller
+            DL_I2C_disableController(I2C_controller_INST);
+            DL_I2C_enableController(I2C_controller_INST);
+        }
+    }
+
+    //printf("I2C Scan Complete!\n");
+}
+
+/*Function for Multiplexer*/
+
+void Multiplexer_SelectChannel(uint8_t channel)
+{
+    if (channel > 7) {
+        printf("ERROR: Invalid Multiplexer Channel! Must be 0-7.\n");
+        return;
+    }
+    uint8_t data = (channel);
+    //printf("Selecting Multiplexer I2C Channel: 0x%02X\n", data);
+
+    // Ensure bus is idle before starting communication
+    while (DL_I2C_getControllerStatus(I2C_controller_INST) & DL_I2C_CONTROLLER_STATUS_BUSY_BUS);
+
+    // SEND Command to Multiplexer
+    DL_I2C_startControllerTransfer(I2C_controller_INST, MULTIPLEXER_I2C_ADDR, DL_I2C_CONTROLLER_DIRECTION_TX, 1);
+    DL_I2C_fillControllerTXFIFO(I2C_controller_INST, &data, 1);
+
+    // **Ensure STOP condition is sent**
+    while (DL_I2C_getControllerStatus(I2C_controller_INST) & DL_I2C_CONTROLLER_STATUS_BUSY_BUS);
+
+    // **Slightly Increase Delay for Multiplexer to Process Command**
+    delay_cycles(30000); 
+
+    // Verify Multiplexer Response:
+    //uint8_t response= 0x00;
+    DL_I2C_startControllerTransfer(I2C_controller_INST, MULTIPLEXER_I2C_ADDR, DL_I2C_CONTROLLER_DIRECTION_RX, 1);
+
+    // Wait for a response from the multiplexer
+    while (DL_I2C_getControllerStatus(I2C_controller_INST) & DL_I2C_CONTROLLER_STATUS_BUSY_BUS);
+    //uint8_t response = DL_I2C_receiveControllerData(I2C_controller_INST);
+
+    // **Debug: Print Expected vs. Received Response**
+    //printf("Multiplexer Response: 0x%02X (Expected: 0x%02X)\n", response, data);
+    
+    
+    // **CHECK FOR ADDRESS ACKNOWLEDGMENT**
+    //(if (!(DL_I2C_getControllerStatus(I2C_controller_INST) & DL_I2C_CONTROLLER_STATUS_ERROR)) {
+    //    printf("Multiplexer detected at 0x70.\n");
+    //    return;
+    //} else{
+    //    printf("ERROR: Multiplexer (0x70) detected.\n");
+    //}
+
+    // Wait for transaction completion
+    //while (DL_I2C_getControllerStatus(I2C_controller_INST) & DL_I2C_CONTROLLER_STATUS_BUSY_BUS);
+
+    //if(response != data){
+    //    printf("ERROR: Multiplexer did not set the correct channel!\n");
+        // **Retry Mechanism: Attempt to Set the Channel Again**
+    //    delay_cycles(10000);
+    //    Multiplexer_SelectChannel(channel);
+    //} else {
+    //    printf("Multiplexer Active Channel: 0x%X\n", data);
+    //    return;
+    //}
+}
+
+void Reset_I2C_Bus() {
+    printf("I2C Bus is stuck! Resetting...\n");
+    
+    // Disable I2C Controller
+    DL_I2C_disableController(I2C_controller_INST);
+    delay_cycles(50000);
+
+    // Re-enable I2C Controller
+    DL_I2C_enableController(I2C_controller_INST);
+    delay_cycles(50000);
+
+    // Check if bus is free now
+    uint32_t status = DL_I2C_getControllerStatus(I2C_controller_INST);
+    printf("I2C Bus Status After Reset: 0x%08X\n", status);
+}

+ 12 - 0
src/peripherals/mux/multiplexer.h

@@ -0,0 +1,12 @@
+#ifndef MULTIPLEXER_H_
+#define MULTIPLEXER_H_
+
+#include <stdint.h>
+
+#define MULTIPLEXER_I2C_ADDR           (0x70)
+//For Channel 0 Hex Value is 0x01
+#define I2C_CHANNEL                    (0x01)
+
+void Multiplexer_SelectChannel(uint8_t channel);
+void I2C_scanBus();
+#endif