In this task, we are implementing a system where a potentiometer connected to the Master microcontroller is rotated, and the Slave microcontroller controls the brightness of an LED connected to it using I2C communication.
For this, we have to establish I2C communication between the master and the slave.
I²C (Inter-Integrated Circuit) is a serial communication protocol that uses only two lines
Key characteristics:
Note: When interfacing I²C devices operating at different voltages (e.g., 5 V ↔ 3.3 V), always use a voltage level shifter to ensure safe logic levels and reliable communication.
So, by connecting and configuring the master and slave devices and the I2C communication, we can implement the task.
Below are the solutions to the given task using different microcontrollers
We’re using an STM32 NUCLEO-F103RB board for both as master and slave, which operates at a 3.3V logic level.
Circuit Diagram
Project Setup in STM32CubeIDE
SystemClock_Config
).HAL_Init()
→ Initializes HAL and system tick.SystemClock_Config()
→ Configures system clock (HSI + PLL).MX_GPIO_Init()
→ Initializes GPIO ports.MX_ADC1_Init()
→ Configures ADC1 for analog input.MX_USART2_UART_Init()
→ Configures UART2.MX_I2C1_Init()
→ Configures I2C1.I2C Initialization (MX_I2C1_Init)
hi2c1.Instance = I2C1;
hi2c1.Init.ClockSpeed = 100000; // 100kHz
hi2c1.Init.DutyCycle = I2C_DUTYCYCLE_2;
hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
if (HAL_I2C_Init(&hi2c1) != HAL_OK) {
Error_Handler();
}
Initializes I2C1 peripheral with 100kHz clock speed, standard duty cycle, and 7-bit addressing mode.
ADC Initialization (MX_ADC1_Init)
hadc1.Instance = ADC1;
hadc1.Init.ScanConvMode = ADC_SCAN_DISABLE;
hadc1.Init.ContinuousConvMode = DISABLE;
hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START;
if (HAL_ADC_Init(&hadc1) != HAL_OK) Error_Handler();
sConfig.Channel = ADC_CHANNEL_0;
sConfig.Rank = ADC_REGULAR_RANK_1;
sConfig.SamplingTime = ADC_SAMPLETIME_239CYCLES_5;
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) Error_Handler();
Initializes ADC1 in single-channel mode, software-triggered conversion, with Channel 0 configured for a 239.5-cycle sampling time.
Private defines and variables
#define SLAVE_ADDRESS (0x08 << 1) // STM32 I2C uses 7-bit addr shifted left by 1
uint16_t adcMaxValue = 4095; // 12-bit ADC max value (2^12 - 1)
uint16_t adcValue = 0; // Stores current ADC reading
uint8_t i2cData[4]; // Buffer for I2C data transmission
Defines I2C slave address (0x08 in 7-bit format) and declares variables for ADC simulation (12-bit resolution) and I2C data buffer.
Main Loop Logic
while (1) {
HAL_ADC_Start(&hadc1);
HAL_ADC_PollForConversion(&hadc1, 20);
adcValue = HAL_ADC_GetValue(&hadc1);
// Break 16-bit values into 8-bit low/high bytes (little endian)
i2cData[0] = adcMaxValue & 0xFF; // Low byte
i2cData[1] = (adcMaxValue >> 8) & 0xFF; // High byte
i2cData[2] = adcValue & 0xFF; // Low byte
i2cData[3] = (adcValue >> 8) & 0xFF; // High byte
HAL_I2C_Master_Transmit(&hi2c1, SLAVE_ADDRESS, i2cData, 4, HAL_MAX_DELAY);
HAL_Delay(10); // Delay 10 milli seconds
}
In this code, the microcontroller continuously reads an ADC value and sends it over I2C along with a predefined adcMaxValue
(likely the maximum ADC range, e.g., 4095 for a 12-bit ADC).
Why does sending adcMaxValue
work with just adcValue
:
adcMaxValue
: It tells the receiver the ADC's full-scale range (e.g., 4095), so the receiver can interpret the raw adcValue
(e.g., 2048 = 50% of max). adcMaxValue
(low byte, then high byte).adcValue
(low byte, then high byte).adcMaxValue
to scale adcValue
(e.g., for percentage calculations).Key HAL Functions Used
HAL_ADC_Start(&hadc1)
HAL_ADC_PollForConversion(&hadc1, 20)
HAL_ADC_GetValue(&hadc1)
HAL_I2C_Master_Transmit(&hi2c1, SLAVE_ADDRESS, i2cData, 4, HAL_MAX_DELAY)
HAL_Delay(10)
Expected Output
The complete STM32CubeIDE project (including .ioc configuration, main.c, and HAL files) is available here:
📥 Download Project
Circuit Diagram
Project Setup in STM32CubeIDE
SystemClock_Config
).HAL_Init()
→ Initializes HAL and system tick.SystemClock_Config()
→ Configures system clock (HSI + PLL).MX_GPIO_Init()
→ Initializes GPIO ports.MX_USART2_UART_Init()
→ Configures UART2.MX_I2C1_Init()
→ Configures I2C1.MX_TIM3_Init()
→ Configures TIM3 for PWM output.I2C Initialization (MX_I2C1_Init)
hi2c1.Instance = I2C1;
hi2c1.Init.ClockSpeed = 100000; // 100kHz
hi2c1.Init.DutyCycle = I2C_DUTYCYCLE_2;
hi2c1.Init.OwnAddress1 = 16; // 0x08 << 1
hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
if (HAL_I2C_Init(&hi2c1) != HAL_OK) {
Error_Handler();
}
Configures I2C1 peripheral to operate at 100 kHz in 7-bit addressing mode with a slave address (0x08 << 1). Ensures proper bus timing and address recognition before enabling communication.
PWM Initialization (MX_TIM3_Init)
htim3.Instance = TIM3;
htim3.Init.Prescaler = 0;
htim3.Init.Period = 4095; // 12-bit resolution
if (HAL_TIM_PWM_Init(&htim3) != HAL_OK) {
Error_Handler();
}
Sets up TIM3 in PWM mode with no prescaler and a 4095-period for 12-bit resolution. This enables fine-grained control over LED brightness.
Private Defines and Variables
#define I2C_SLAVE_ADDRESS 0x08
uint8_t i2cRxBuffer[4]; // Buffer for I2C data reception
Declares I2C_SLAVE_ADDRESS for clarity and a 4-byte i2cRxBuffer to store incoming data from the I2C master.
I2C Reception Callback
void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c)
{
// Reconstruct 16-bit values from received bytes
uint16_t adcMaxValue = (i2cRxBuffer[1] << 8) | i2cRxBuffer[0];
uint16_t adcValue = (i2cRxBuffer[3] << 8) | i2cRxBuffer[2];
// Calculate brightness proportionally
uint16_t brightness = 0;
if (adcMaxValue > 0) {
brightness = (uint32_t)adcValue * 4095 / adcMaxValue;
}
// Set PWM duty cycle
__HAL_TIM_SET_COMPARE(&htim3, TIM_CHANNEL_1, brightness);
// Prepare for next reception
HAL_I2C_Slave_Receive_IT(hi2c, i2cRxBuffer, 4);
}
Triggered on data reception, it reconstructs two 16-bit values (ADC max and current reading), calculates proportional PWM duty cycle, updates brightness, and re-arms the I2C receive interrupt.
Main loop logic
HAL_TIM_PWM_Start(&htim3, TIM_CHANNEL_1); // Start PWM
HAL_I2C_Slave_Receive_IT(&hi2c1, i2cRxBuffer, 4); // Start I2C reception
while (1) {
// Main loop - all processing happens in interrupts
}
At startup, PWM generation on TIM3 channel 1 and non-blocking I2C reception on I2C1 are both activated. The infinite while (1) loop remains empty because all real-time processing—data reception, and PWM adjustment—occurs inside interrupt service routines.
Data Processing Explanation
Key HAL Functions Used
HAL_I2C_Slave_Receive_IT()
HAL_I2C_SlaveRxCpltCallback()
__HAL_TIM_SET_COMPARE()
HAL_TIM_PWM_Start()
Expected Output
The complete STM32CubeIDE project (including .ioc configuration, main.c, and HAL files) is available here:
📥 Download Project
We are using the ESP32 DevKit v4 development board and programming it using the Arduino IDE.
In both ESP32 master and slave codes, the Wire.h
library is used for I²C communication.
Solution of the given task:
The I²C slave can be any microcontroller (e.g., Arduino UNO, ESP32, STM32) programmed with the same slave address (0x08). Only the slave code changes.
#include <Wire.h>
#include <driver/gpio.h>
#define potPin 34 // Potentiometer input pin
#define slaveAddress 0x08 // I2C slave address
#define MAX_ADC_VALUE 4095 // Maximum ADC value (12-bit)
uint16_t brightness; // Current potentiometer reading
uint16_t previousvalue; // Previous potentiometer reading
uint8_t error; // I2C transmission error flag
// Disable ESP32’s internal pull-ups/pull-downs on I2C pins
void ensureNoInternalPullups(int sda = 21, int scl = 22) {
gpio_pullup_dis((gpio_num_t)sda);
gpio_pulldown_dis((gpio_num_t)sda);
gpio_pullup_dis((gpio_num_t)scl);
gpio_pulldown_dis((gpio_num_t)scl);
}
void setup() {
Wire.begin(); // Initialize ESP32 as I2C master
ensureNoInternalPullups(); // Disable internal pulls
Serial.begin(115200);
}
void loop() {
brightness = analogRead(potPin); // Read potentiometer value
Serial.println(brightness); // Debug print
// Send only if value has changed
if (brightness != previousvalue) {
Wire.beginTransmission((uint8_t)slaveAddress);
Wire.write(MAX_ADC_VALUE); // Send max ADC value (LSB)
Wire.write(MAX_ADC_VALUE >> 8); // Send max ADC value (MSB)
Wire.write(brightness); // Send brightness (LSB)
Wire.write(brightness >> 8); // Send brightness (MSB)
error = Wire.endTransmission(true); // End transmission
if (error == 0) {
Serial.println("Successful data transmission");
} else {
Serial.println("ERROR in data transmission");
Serial.println(error);
}
previousvalue = brightness; // Update previous value
}
delay(1); // Small delay for stable communication
}
// I2C Slave code for ESP32 that adjusts LED brightness based on data from Master
#include <Wire.h>
#include <driver/gpio.h>
#define slaveAddress 0x08 // I2C slave address
#define LED_PIN 2 // LED connected to GPIO2
#define PWM_FREQ 1000 // PWM frequency: 1 kHz
#define PWM_RES_BIT 12 // PWM resolution: 12-bit (0–4095)
#define PWM_RES 4095
uint16_t brightness = 0; // Variable to store mapped LED brightness
// Function to disable ESP32's internal pull-ups/pull-downs on I2C pins
void ensureNoInternalPullups(int sda = 21, int scl = 22) {
gpio_pullup_dis((gpio_num_t)sda);
gpio_pulldown_dis((gpio_num_t)sda);
gpio_pullup_dis((gpio_num_t)scl);
gpio_pulldown_dis((gpio_num_t)scl);
}
void setup() {
Serial.begin(115200);
// Initialize ESP32 as I2C slave
Wire.begin((uint8_t)slaveAddress);
ensureNoInternalPullups();
Wire.onReceive(receiveEvent); // Register callback for incoming data
// Set up LED PWM (Core v3.x function: ledcAttach)
ledcAttach(LED_PIN, PWM_FREQ, PWM_RES_BIT);
Serial.setDebugOutput(true);
}
void loop() {
// Nothing here, work is interrupt-driven via I2C callback
}
// I2C data receive handler
void receiveEvent(int bytesReceived) {
if (bytesReceived == 4) { // Expecting 4 bytes
// Read data sent by master
uint8_t adcMaxValueLow = Wire.read();
uint8_t adcMaxValueHigh = Wire.read();
uint8_t adcValueLow = Wire.read();
uint8_t adcValueHigh = Wire.read();
// Reconstruct 16-bit values
uint16_t adcMaxValue = (adcMaxValueHigh << 8) | adcMaxValueLow;
uint16_t adcValue = (adcValueHigh << 8) | adcValueLow;
Serial.println(adcValue); // Debug print
// Map ADC value into PWM range
if (adcMaxValue > 0) {
brightness = map(adcValue, 0, adcMaxValue, 0, PWM_RES);
}
// Set LED brightness
ledcWrite(LED_PIN, brightness);
}
}
brightness = map(adcValue, 0, adcMaxValue, 0, PWM_RES);
ledcWrite(LED_PIN, brightness);
We are using the Arduino UNO development board and programming it using the Arduino IDE.
In both Arduino UNO master and slave codes, the Wire.h library is used for I²C communication.
Solution of the given task:
First, let's establish the hardware connection.
Circuit Diagram
#include <Wire.h>
#define potPin A1
#define slaveAddress 0x08 // Slave address
#define MAX_ADC_VALUE 1023
uint16_t brightness;
uint16_t previousvalue;
uint8_t error;
void setup() {
// Initialize Arduino UNO as I2C master
Wire.begin();
// Disable internal pull-ups on SDA/SCL
pinMode(A4, INPUT); // SDA
pinMode(A5, INPUT); // SCL
digitalWrite(A4, LOW); // ensure pull-up is off
digitalWrite(A5, LOW); // ensure pull-up is off
Serial.begin(115200);
}
void loop() {
// It map the potentiometer value(0 to 1023) to PWM value(0 to 255) i.e 1023/255 = ~4
brightness = analogRead(potPin);
if (brightness != previousvalue) {
Wire.beginTransmission(slaveAddress);
Wire.write(MAX_ADC_VALUE);
Wire.write(MAX_ADC_VALUE >> 8);
Wire.write(brightness); // write data in i2c buffer
Wire.write(brightness >> 8);
error = Wire.endTransmission(); // send brightness value using i2c
if (error == 0) {
Serial.println("Successful data transmission");
} else {
Serial.println("ERROR in data transmission");
}
previousvalue = brightness;
}
delay(10); // time duration for proper communication
}
Code Explanation (Master)
Wire.begin()
: Initializes Arduino UNO as I²C master. pinMode(A4, INPUT)
and pinMode(A5, INPUT)
with digitalWrite(A4, LOW)
and digitalWrite(A5, LOW)
ensure that internal pull-ups are disabled because external 4.7 kΩ pull-up resistors are used for SDA and SCL lines.brightness = analogRead(potPin);
reads the potentiometer value (0–1023). if (brightness != previousvalue)
ensures data is sent only when the potentiometer value changes, reducing unnecessary I²C traffic.Wire.beginTransmission(slaveAddress)
starts I²C communication with the slave.Wire.write(MAX_ADC_VALUE);
Wire.write(MAX_ADC_VALUE>>8); sends the reference maximum ADC value (two bytes).Wire.write(brightness); Wire.write(brightness>>8);
sends the current potentiometer value (two bytes).Wire.endTransmission()
completes the transaction and returns an error code (0 = success).delay(10);
adds a short pause to maintain proper communication timing.First, let's establish the hardware connection.
Code(Slave)
#include <Wire.h>
#define slaveAddress 0x08
#define ledPin 9
void setup() {
// Initialize arduino as I2C slave (Slave address is 0x08)
Wire.begin(slaveAddress);
// Disable internal pull-ups on SDA/SCL
pinMode(A4, INPUT); // SDA
pinMode(A5, INPUT); // SCL
digitalWrite(A4, LOW); // ensure pull-up is off
digitalWrite(A5, LOW); // ensure pull-up is off
Wire.onReceive(receiveEvent);
pinMode(ledPin, OUTPUT);
}
void loop() {
// Nothing to do in loop
}
void receiveEvent(int bytesReceived) {
if (bytesReceived == 4) {
uint8_t adcMaxValueLow = Wire.read();
uint8_t adcMaxValueHigh = Wire.read();
uint8_t adcValueLow = Wire.read();
uint8_t adcValueHigh = Wire.read();
uint16_t adcMaxValue = (adcMaxValueHigh << 8) | adcMaxValueLow;
uint16_t adcValue = (adcValueHigh << 8) | adcValueLow;
uint8_t brightness = 0;
if (adcMaxValue > 0) {
brightness = map(adcValue, 0, adcMaxValue, 0, 255);
}
analogWrite(ledPin, brightness);
}
}
Wire.begin(slaveAddress):
pinMode(A4, INPUT)
and pinMode(A5, INPUT)
with digitalWrite(A4, LOW)
and digitalWrite(A5, LOW)
ensure internal pull-ups on SDA and SCL are disabled because external 4.7 kΩ pull-up resistors are used.Wire.onReceive(receiveEvent):
pinMode(ledPin, OUTPUT):
receiveEvent()
Function if (bytesReceived == 4)
ensures that the master sends exactly 4 bytes (two for adcMaxValue
, two for adcValue).adcMaxValueLow
and adcMaxValueHigh
store the two bytes of MAX_ADC_VALUE
.adcValueLow
and adcValueHigh
store the two bytes of the current potentiometer value.adcMaxValue = (adcMaxValueHigh << 8) | adcMaxValueLow;
adcValue = (adcValueHigh << 8) | adcValueLow;
If adcMaxValue > 0, use map(adcValue, 0, adcMaxValue, 0, 255)
to scale the potentiometer value to a PWM range (0–255).Hardware Setup