ESP32 MQTT Publish DS18B20 Sensor Readings to Node-Red using ESP-IDF

In this ESP-IDF project, we will learn to publish DS18B20 sensor readings to Node-Red with ESP32 MQTT. We will perform MQTT communication with ESP32 and Node-Red and publish and subscribe to MQTT topics. The ESP32 development board will act as an MQTT publisher and Node-Red will act as a subscriber. Using MQTT protocol, the ESP32 will publish DS18B20 sensor readings on the Node-Red Dashboard which will subscribe to the corresponding MQTT topics. The sensor data constituting of temperature readings in both degree Celsius and degree Fahrenheit will be interactively displayed on the Node-Red Dashboard.

We will use Mosquitto MQTT Broker on Raspberry Pi but you can install it on your Windows and Linux machine also, if you are using them instead. The publisher and subscriber will make connections with the MQTT broker installed on Raspberry Pi. After that, the ESP32 will publish sensor data to the Node-Red dashboard on the specified topics.

Before we move ahead, make sure you have the latest version of VS Code installed on your system with the ESP-IDF extension configured.

ESP32 ESP-IDF MQTT Publish DS18B20 Sensor Readings to Node-Red

Our aim is to create a project that uses ESP32 MQTT protocol using ESP-IDF to publish DS18B20 sensor readings to Node-Red. Let us look the steps that are involved in this project.

  1. The ESP32 board is interfaced with a DS18B20 sensor which is used to measure the relative humidity and the ambient temperature. This ESP32 board will connect to the MQTT broker. In our case, we will use Mosquitto broker on Raspberry Pi. If you want to know how to successfully install the broker on your Raspberry Pi, you can refer to the following guide: (Install Mosquitto MQTT Broker on Raspberry Pi
  2. After acquiring the sensor data from the DS18B20 sensor, the ESP32 board publishes these readings on individual MQTT topics.: esp32/ds18b20/temperatureC is for publishing DS18B20 temperature readings in degree Celsius and esp32/ds18b20/temperatureF is for publishing DS18B20 temperature readings in degree Fahrenheit.
  3. Node-Red will subscribe to these two topics. Therefore, it will be able to receive the sensor readings and interactively display them in its dashboard with the help of gauges.
ESP-IDF MQTT DS18B20 Readings with Node-Red Project Overview

Interfacing DS18B20 with ESP32

The DS18B20 temperature sensor is widely used in electronic projects that uses a single wire to acquire data, therefore claiming it as single wire programmable in nature. It uses a single GPIO pin of the microcontroller to output the current temperature reading of its surroundings. By using the least number of pins, we can conveniently access multiple temperature readings by hooking up DS18B20 sensors on the same GPIO pin.

We will need the following components to connect our ESP32 board with the DS18B20 sensor.

  1. ESP32 board
  2. DS18B20 Sensor
  3. 4.7k ohm pull up resistor
  4. Connecting Wires
  5. Breadboard

The DS18B20 sensor can be powered on in two different modes. which are the normal mode and the parasite mode. In the normal mode, an external source powers the sensor through the VCC pin and the 4.7k ohm resistor. However, in the parasite mode, the sensor is powered from the data line therefore no external power source is required. We will power our DS18B20 sensor in the normal mode.

The table below shows the connections of the three pins of DS18B20 sensor with the ESP32 board.

DS18B20ESP32
VCC3.3V / Vin
DataGPIO4
GNDGND

Connect VCC pin of the sensor with 3.3V pin or Vin pin of the ESP32 board and common the grounds of the two devices. Moreover, connect the data pin of the sensor with an appropriate GPIO pin of the ESP32 board which can be set up as an output pin. Note GPIO34-39 are input only pins and can not be used to drive the one wire bus. We are using GPIO4 to connect with the data pin through the 4.7k ohm pull up resistor. One end of the resistor will be connected with the data output and the other end will be connected with the power supply.

Note that if you are using the DS18B20 module instead, then you do not need to add the external pull up resistor. This is because the module already comes up with a sensor and an onboard pull up resistor.

Follow the schematic diagram below to connect the two devices together.

ESP32 with DS18B20 sensor schematic diagram

You may also like to read:

ESP32 MQTT DS18B20 Readings with Node-Red and ESP-IDF

We will build and create a project in VS Code with ESP-IDF extension. The code will read temperature readings by using the DS18B20 library and then use mqtt_client library to connect ESP32 with the MQTT broker, and publish the readings on different topics. We will use a simple DS18B20 library for a single DS18B20 sensor with ESP32. It is provided by feelfreelinux on GitHub.

Create Example Project

Open your VS Code and head over to View > Command Palette. Type ESP-IDF: New Project in the search bar and press enter.

Specify the project name and directory, along with the ESP-IDF board and target. For the ESP-IDF board, we have chosen the custom board option. For ESP-IDF target, we have chosen ESP32 module. Click ‘Choose Template’ button to proceed forward.

In the Extension, select ESP-IDF option:

ESP-IDF in VS Code New Project 2

We will click the ‘sample_project’ under the get-started tab. Now click ‘Create project using template sample_project.’

ESP-IDF in VS Code New Project 3

You will get a notification that the project has been created. To open the project in a new window, click ‘Yes.’

This opens the project that we created inside the EXPLORER tab. There are several folders inside our project folder. This is the same for every project which you will create through ESP-IDF Explorer.

  • First, let’s add the necessary header files for the libraries required for this project. Create a new folder called ‘components’ and add the following files listed below:
ESP-IDF MQTT DS18B20 Readings with Node-Red Add DS18B20 Libraries

CMakeLists.txt

idf_component_register(SRCS "ds18b20.c"
                    INCLUDE_DIRS "include")

ds18b20.h

/*
    This program is free software: you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.
    This program is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.
    You should have received a copy of the GNU General Public License
    along with this program.  If not, see <http://www.gnu.org/licenses/>.
*/
#include <esp_system.h>

#ifndef DS18B20_H_  
#define DS18B20_H_

#define noInterrupts() portMUX_TYPE mux = portMUX_INITIALIZER_UNLOCKED;taskENTER_CRITICAL(&mux)
#define interrupts() taskEXIT_CRITICAL(&mux)

#define DEVICE_DISCONNECTED_C -127
#define DEVICE_DISCONNECTED_F -196.6
#define DEVICE_DISCONNECTED_RAW -7040
#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
#define pgm_read_byte(addr)   (*(const unsigned char *)(addr))

typedef uint8_t DeviceAddress[8];
typedef uint8_t ScratchPad[9];

// Dow-CRC using polynomial X^8 + X^5 + X^4 + X^0
// Tiny 2x16 entry CRC table created by Arjen Lentz
// See http://lentz.com.au/blog/calculating-crc-with-a-tiny-32-entry-lookup-table
static const uint8_t dscrc2x16_table[] = {
	0x00, 0x5E, 0xBC, 0xE2, 0x61, 0x3F, 0xDD, 0x83,
	0xC2, 0x9C, 0x7E, 0x20, 0xA3, 0xFD, 0x1F, 0x41,
	0x00, 0x9D, 0x23, 0xBE, 0x46, 0xDB, 0x65, 0xF8,
	0x8C, 0x11, 0xAF, 0x32, 0xCA, 0x57, 0xE9, 0x74
};

/* *INDENT-OFF* */
#ifdef __cplusplus
    extern "C" {
#endif
/* *INDENT-ON* */

void ds18b20_init(int GPIO);

#define ds18b20_send ds18b20_write
#define ds18b20_send_byte ds18b20_write_byte
#define ds18b20_RST_PULSE ds18b20_reset

void ds18b20_write(char bit);
unsigned char ds18b20_read(void);
void ds18b20_write_byte(char data);
unsigned char ds18b20_read_byte(void);
unsigned char ds18b20_reset(void);

bool ds18b20_setResolution(const DeviceAddress tempSensorAddresses[], int numAddresses, uint8_t newResolution);
bool ds18b20_isConnected(const DeviceAddress *deviceAddress, uint8_t *scratchPad);
void ds18b20_writeScratchPad(const DeviceAddress *deviceAddress, const uint8_t *scratchPad);
bool ds18b20_readScratchPad(const DeviceAddress *deviceAddress, uint8_t *scratchPad);
void ds18b20_select(const DeviceAddress *address);
uint8_t ds18b20_crc8(const uint8_t *addr, uint8_t len);
bool ds18b20_isAllZeros(const uint8_t * const scratchPad);
bool isConversionComplete();
uint16_t millisToWaitForConversion();

void ds18b20_requestTemperatures();
float ds18b20_getTempF(const DeviceAddress *deviceAddress);
float ds18b20_getTempC(const DeviceAddress *deviceAddress);
int16_t calculateTemperature(const DeviceAddress *deviceAddress, uint8_t* scratchPad);
float ds18b20_get_temp(void);

void reset_search();
bool search(uint8_t *newAddr, bool search_mode);

/* *INDENT-OFF* */
#ifdef __cplusplus
    }
#endif
/* *INDENT-ON* */

#endif

ds18b20.c

/*
    This program is free software: you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.
    This program is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.
    You should have received a copy of the GNU General Public License
     along with this program.  If not, see <http://www.gnu.org/licenses/>.
*/
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "driver/gpio.h"
#include "esp32/rom/ets_sys.h"
#include "ds18b20.h"

// OneWire commands
#define GETTEMP			0x44  // Tells device to take a temperature reading and put it on the scratchpad
#define SKIPROM			0xCC  // Command to address all devices on the bus
#define SELECTDEVICE	0x55  // Command to address all devices on the bus
#define COPYSCRATCH     0x48  // Copy scratchpad to EEPROM
#define READSCRATCH     0xBE  // Read from scratchpad
#define WRITESCRATCH    0x4E  // Write to scratchpad
#define RECALLSCRATCH   0xB8  // Recall from EEPROM to scratchpad
#define READPOWERSUPPLY 0xB4  // Determine if device needs parasite power
#define ALARMSEARCH     0xEC  // Query bus for devices with an alarm condition
// Scratchpad locations
#define TEMP_LSB        0
#define TEMP_MSB        1
#define HIGH_ALARM_TEMP 2
#define LOW_ALARM_TEMP  3
#define CONFIGURATION   4
#define INTERNAL_BYTE   5
#define COUNT_REMAIN    6
#define COUNT_PER_C     7
#define SCRATCHPAD_CRC  8
// DSROM FIELDS
#define DSROM_FAMILY    0
#define DSROM_CRC       7
// Device resolution
#define TEMP_9_BIT  0x1F //  9 bit
#define TEMP_10_BIT 0x3F // 10 bit
#define TEMP_11_BIT 0x5F // 11 bit
#define TEMP_12_BIT 0x7F // 12 bit

uint8_t DS_GPIO;
uint8_t init=0;
uint8_t bitResolution=12;
uint8_t devices=0;

DeviceAddress ROM_NO;
uint8_t LastDiscrepancy;
uint8_t LastFamilyDiscrepancy;
bool LastDeviceFlag;

/// Sends one bit to bus
void ds18b20_write(char bit){
	if (bit & 1) {
		gpio_set_direction(DS_GPIO, GPIO_MODE_OUTPUT);
		noInterrupts();
		gpio_set_level(DS_GPIO,0);
		ets_delay_us(6);
		gpio_set_direction(DS_GPIO, GPIO_MODE_INPUT);	// release bus
		ets_delay_us(64);
		interrupts();
	} else {
		gpio_set_direction(DS_GPIO, GPIO_MODE_OUTPUT);
		noInterrupts();
		gpio_set_level(DS_GPIO,0);
		ets_delay_us(60);
		gpio_set_direction(DS_GPIO, GPIO_MODE_INPUT);	// release bus
		ets_delay_us(10);
		interrupts();
	}
}

// Reads one bit from bus
unsigned char ds18b20_read(void){
	unsigned char value = 0;
	gpio_set_direction(DS_GPIO, GPIO_MODE_OUTPUT);
	noInterrupts();
	gpio_set_level(DS_GPIO, 0);
	ets_delay_us(6);
	gpio_set_direction(DS_GPIO, GPIO_MODE_INPUT);
	ets_delay_us(9);
	value = gpio_get_level(DS_GPIO);
	ets_delay_us(55);
	interrupts();
	return (value);
}
// Sends one byte to bus
void ds18b20_write_byte(char data){
  unsigned char i;
  unsigned char x;
  for(i=0;i<8;i++){
    x = data>>i;
    x &= 0x01;
    ds18b20_write(x);
  }
  ets_delay_us(100);
}
// Reads one byte from bus
unsigned char ds18b20_read_byte(void){
  unsigned char i;
  unsigned char data = 0;
  for (i=0;i<8;i++)
  {
    if(ds18b20_read()) data|=0x01<<i;
    ets_delay_us(15);
  }
  return(data);
}
// Sends reset pulse
unsigned char ds18b20_reset(void){
	unsigned char presence;
	gpio_set_direction(DS_GPIO, GPIO_MODE_OUTPUT);
	noInterrupts();
	gpio_set_level(DS_GPIO, 0);
	ets_delay_us(480);
	gpio_set_level(DS_GPIO, 1);
	gpio_set_direction(DS_GPIO, GPIO_MODE_INPUT);
	ets_delay_us(70);
	presence = (gpio_get_level(DS_GPIO) == 0);
	ets_delay_us(410);
	interrupts();
	return presence;
}

bool ds18b20_setResolution(const DeviceAddress tempSensorAddresses[], int numAddresses, uint8_t newResolution) {
	bool success = false;
	// handle the sensors with configuration register
	newResolution = constrain(newResolution, 9, 12);
	uint8_t newValue = 0;
	ScratchPad scratchPad;
	// loop through each address
	for (int i = 0; i < numAddresses; i++){
		// we can only update the sensor if it is connected
		if (ds18b20_isConnected((DeviceAddress*) tempSensorAddresses[i], scratchPad)) {
			switch (newResolution) {
			case 12:
				newValue = TEMP_12_BIT;
				break;
			case 11:
				newValue = TEMP_11_BIT;
				break;
			case 10:
				newValue = TEMP_10_BIT;
				break;
			case 9:
			default:
				newValue = TEMP_9_BIT;
				break;
			}
			// if it needs to be updated we write the new value
			if (scratchPad[CONFIGURATION] != newValue) {
				scratchPad[CONFIGURATION] = newValue;
				ds18b20_writeScratchPad((DeviceAddress*) tempSensorAddresses[i], scratchPad);
			}
			// done
			success = true;
		}
	}
	return success;
}

void ds18b20_writeScratchPad(const DeviceAddress *deviceAddress, const uint8_t *scratchPad) {
	ds18b20_reset();
	ds18b20_select(deviceAddress);
	ds18b20_write_byte(WRITESCRATCH);
	ds18b20_write_byte(scratchPad[HIGH_ALARM_TEMP]); // high alarm temp
	ds18b20_write_byte(scratchPad[LOW_ALARM_TEMP]); // low alarm temp
	ds18b20_write_byte(scratchPad[CONFIGURATION]);
	ds18b20_reset();
}

bool ds18b20_readScratchPad(const DeviceAddress *deviceAddress, uint8_t* scratchPad) {
	// send the reset command and fail fast
	int b = ds18b20_reset();
	if (b == 0) return false;
	ds18b20_select(deviceAddress);
	ds18b20_write_byte(READSCRATCH);
	// Read all registers in a simple loop
	// byte 0: temperature LSB
	// byte 1: temperature MSB
	// byte 2: high alarm temp
	// byte 3: low alarm temp
	// byte 4: DS18B20 & DS1822: configuration register
	// byte 5: internal use & crc
	// byte 6: DS18B20 & DS1822: store for crc
	// byte 7: DS18B20 & DS1822: store for crc
	// byte 8: SCRATCHPAD_CRC
	for (uint8_t i = 0; i < 9; i++) {
		scratchPad[i] = ds18b20_read_byte();
	}
	b = ds18b20_reset();
	return (b == 1);
}

void ds18b20_select(const DeviceAddress *address){
    uint8_t i;
    ds18b20_write_byte(SELECTDEVICE);           // Choose ROM
    for (i = 0; i < 8; i++) ds18b20_write_byte(((uint8_t *)address)[i]);
}

void ds18b20_requestTemperatures(){
	ds18b20_reset();
	ds18b20_write_byte(SKIPROM);
	ds18b20_write_byte(GETTEMP);
    unsigned long start = esp_timer_get_time() / 1000ULL;
    while (!isConversionComplete() && ((esp_timer_get_time() / 1000ULL) - start < millisToWaitForConversion())) vPortYield();
}

bool isConversionComplete() {
	uint8_t b = ds18b20_read();
	return (b == 1);
}

uint16_t millisToWaitForConversion() {
	switch (bitResolution) {
	case 9:
		return 94;
	case 10:
		return 188;
	case 11:
		return 375;
	default:
		return 750;
	}
}

bool ds18b20_isConnected(const DeviceAddress *deviceAddress, uint8_t *scratchPad) {
	bool b = ds18b20_readScratchPad(deviceAddress, scratchPad);
	return b && !ds18b20_isAllZeros(scratchPad) && (ds18b20_crc8(scratchPad, 8) == scratchPad[SCRATCHPAD_CRC]);
}

uint8_t ds18b20_crc8(const uint8_t *addr, uint8_t len){
	uint8_t crc = 0;
	while (len--) {
		crc = *addr++ ^ crc;  // just re-using crc as intermediate
		crc = pgm_read_byte(dscrc2x16_table + (crc & 0x0f)) ^
		pgm_read_byte(dscrc2x16_table + 16 + ((crc >> 4) & 0x0f));
	}
	return crc;
}

bool ds18b20_isAllZeros(const uint8_t * const scratchPad) {
	for (size_t i = 0; i < 9; i++) {
		if (scratchPad[i] != 0) {
			return false;
		}
	}
	return true;
}

float ds18b20_getTempF(const DeviceAddress *deviceAddress) {
	ScratchPad scratchPad;
	if (ds18b20_isConnected(deviceAddress, scratchPad)){
		int16_t rawTemp = calculateTemperature(deviceAddress, scratchPad);
		if (rawTemp <= DEVICE_DISCONNECTED_RAW)
			return DEVICE_DISCONNECTED_F;
		// C = RAW/128
		// F = (C*1.8)+32 = (RAW/128*1.8)+32 = (RAW*0.0140625)+32
		return ((float) rawTemp * 0.0140625f) + 32.0f;
	}
	return DEVICE_DISCONNECTED_F;
}

float ds18b20_getTempC(const DeviceAddress *deviceAddress) {
	ScratchPad scratchPad;
	if (ds18b20_isConnected(deviceAddress, scratchPad)){
		int16_t rawTemp = calculateTemperature(deviceAddress, scratchPad);
		if (rawTemp <= DEVICE_DISCONNECTED_RAW)
			return DEVICE_DISCONNECTED_F;
		// C = RAW/128
		// F = (C*1.8)+32 = (RAW/128*1.8)+32 = (RAW*0.0140625)+32
		return (float) rawTemp/128.0f;
	}
	return DEVICE_DISCONNECTED_F;
}

// reads scratchpad and returns fixed-point temperature, scaling factor 2^-7
int16_t calculateTemperature(const DeviceAddress *deviceAddress, uint8_t* scratchPad) {
	int16_t fpTemperature = (((int16_t) scratchPad[TEMP_MSB]) << 11) | (((int16_t) scratchPad[TEMP_LSB]) << 3);
	return fpTemperature;
}

// Returns temperature from sensor
float ds18b20_get_temp(void) {
  if(init==1){
    unsigned char check;
    char temp1=0, temp2=0;
      check=ds18b20_RST_PULSE();
      if(check==1)
      {
        ds18b20_send_byte(0xCC);
        ds18b20_send_byte(0x44);
        vTaskDelay(750 / portTICK_RATE_MS);
        check=ds18b20_RST_PULSE();
        ds18b20_send_byte(0xCC);
        ds18b20_send_byte(0xBE);
        temp1=ds18b20_read_byte();
        temp2=ds18b20_read_byte();
        check=ds18b20_RST_PULSE();
        float temp=0;
        temp=(float)(temp1+(temp2*256))/16;
        return temp;
      }
      else{return 0;}

  }
  else{return 0;}
}

void ds18b20_init(int GPIO) {
	DS_GPIO = GPIO;
	gpio_pad_select_gpio(DS_GPIO);
	init = 1;
}

//
// You need to use this function to start a search again from the beginning.
// You do not need to do it for the first search, though you could.
//
void reset_search() {
	devices=0;
	// reset the search state
	LastDiscrepancy = 0;
	LastDeviceFlag = false;
	LastFamilyDiscrepancy = 0;
	for (int i = 7; i >= 0; i--) {
		ROM_NO[i] = 0;
	}
}
// --- Replaced by the one from the Dallas Semiconductor web site ---
//--------------------------------------------------------------------------
// Perform the 1-Wire Search Algorithm on the 1-Wire bus using the existing
// search state.
// Return TRUE  : device found, ROM number in ROM_NO buffer
//        FALSE : device not found, end of search

bool search(uint8_t *newAddr, bool search_mode) {
	uint8_t id_bit_number;
	uint8_t last_zero, rom_byte_number;
	bool search_result;
	uint8_t id_bit, cmp_id_bit;

	unsigned char rom_byte_mask, search_direction;

	// initialize for search
	id_bit_number = 1;
	last_zero = 0;
	rom_byte_number = 0;
	rom_byte_mask = 1;
	search_result = false;

	// if the last call was not the last one
	if (!LastDeviceFlag) {
		// 1-Wire reset
		if (!ds18b20_reset()) {
			// reset the search
			LastDiscrepancy = 0;
			LastDeviceFlag = false;
			LastFamilyDiscrepancy = 0;
			return false;
		}

		// issue the search command
		if (search_mode == true) {
			ds18b20_write_byte(0xF0);   // NORMAL SEARCH
		} else {
			ds18b20_write_byte(0xEC);   // CONDITIONAL SEARCH
		}

		// loop to do the search
		do {
			// read a bit and its complement
			id_bit = ds18b20_read();
			cmp_id_bit = ds18b20_read();

			// check for no devices on 1-wire
			if ((id_bit == 1) && (cmp_id_bit == 1)) {
				break;
			} else {
				// all devices coupled have 0 or 1
				if (id_bit != cmp_id_bit) {
					search_direction = id_bit;  // bit write value for search
				} else {
					// if this discrepancy if before the Last Discrepancy
					// on a previous next then pick the same as last time
					if (id_bit_number < LastDiscrepancy) {
						search_direction = ((ROM_NO[rom_byte_number]
								& rom_byte_mask) > 0);
					} else {
						// if equal to last pick 1, if not then pick 0
						search_direction = (id_bit_number == LastDiscrepancy);
					}
					// if 0 was picked then record its position in LastZero
					if (search_direction == 0) {
						last_zero = id_bit_number;

						// check for Last discrepancy in family
						if (last_zero < 9)
							LastFamilyDiscrepancy = last_zero;
					}
				}

				// set or clear the bit in the ROM byte rom_byte_number
				// with mask rom_byte_mask
				if (search_direction == 1)
					ROM_NO[rom_byte_number] |= rom_byte_mask;
				else
					ROM_NO[rom_byte_number] &= ~rom_byte_mask;

				// serial number search direction write bit
				ds18b20_write(search_direction);

				// increment the byte counter id_bit_number
				// and shift the mask rom_byte_mask
				id_bit_number++;
				rom_byte_mask <<= 1;

				// if the mask is 0 then go to new SerialNum byte rom_byte_number and reset mask
				if (rom_byte_mask == 0) {
					rom_byte_number++;
					rom_byte_mask = 1;
				}
			}
		} while (rom_byte_number < 8);  // loop until through all ROM bytes 0-7

		// if the search was successful then
		if (!(id_bit_number < 65)) {
			// search successful so set LastDiscrepancy,LastDeviceFlag,search_result
			LastDiscrepancy = last_zero;

			// check for last device
			if (LastDiscrepancy == 0) {
				LastDeviceFlag = true;
			}
			search_result = true;
		}
	}

	// if no device found then reset counters so next 'search' will be like a first
	if (!search_result || !ROM_NO[0]) {
		devices=0;
		LastDiscrepancy = 0;
		LastDeviceFlag = false;
		LastFamilyDiscrepancy = 0;
		search_result = false;
	} else {
		for (int i = 0; i < 8; i++){
			newAddr[i] = ROM_NO[i];
		}
		devices++;
	}
	return search_result;
}
  • Now head over to the main.c file. The main folder contains the source code meaning the main.c file will be found here. Go to main > main.c and open it. Copy the code given below in that file and save it.

ESP32 ESP-IDF MQTT DS18B20 Code

#include <stdio.h>
#include <stdint.h>
#include <stddef.h>
#include <string.h>
#include "esp_wifi.h"
#include "esp_system.h"
#include "nvs_flash.h"
#include "esp_event.h"
#include "esp_netif.h"
#include "rom/ets_sys.h"
#include "driver/gpio.h"
#include "sdkconfig.h"

#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#include "freertos/queue.h"

#include "lwip/sockets.h"
#include "lwip/dns.h"
#include "lwip/netdb.h"

#include "esp_log.h"
#include "mqtt_client.h"
#include "ds18b20.h" 

const int DS_PIN = 4;

static const char *TAG = "MQTT_EXAMPLE";

#define EXAMPLE_ESP_WIFI_SSID "YOUR_SSID"
#define EXAMPLE_ESP_WIFI_PASS "YOUR_PASSWORD"

#define MAX_RETRY 10
static int retry_cnt = 0;

#define MQTT_PUB_TEMPC_DS18B20 "esp32/ds18b20/temperatureC"
#define MQTT_PUB_TEMPF_DS18B20 "esp32/ds18b20/temperatureF"

uint32_t MQTT_CONNECTED = 0;

static void mqtt_app_start(void);

static esp_err_t wifi_event_handler(void *arg, esp_event_base_t event_base,
                                    int32_t event_id, void *event_data)
{
    switch (event_id)
    {
    case WIFI_EVENT_STA_START:
        esp_wifi_connect();
        ESP_LOGI(TAG, "Trying to connect with Wi-Fi\n");
        break;

    case WIFI_EVENT_STA_CONNECTED:
        ESP_LOGI(TAG, "Wi-Fi connected\n");
        break;

    case IP_EVENT_STA_GOT_IP:
        ESP_LOGI(TAG, "got ip: startibg MQTT Client\n");
        mqtt_app_start();
        break;

    case WIFI_EVENT_STA_DISCONNECTED:
        ESP_LOGI(TAG, "disconnected: Retrying Wi-Fi\n");
        if (retry_cnt++ < MAX_RETRY)
        {
            esp_wifi_connect();
        }
        else
            ESP_LOGI(TAG, "Max Retry Failed: Wi-Fi Connection\n");
        break;

    default:
        break;
    }
    return ESP_OK;
}

void wifi_init(void)
{
    esp_event_loop_create_default();
    esp_event_handler_register(WIFI_EVENT, ESP_EVENT_ANY_ID, &wifi_event_handler, NULL);
    esp_event_handler_register(IP_EVENT, IP_EVENT_STA_GOT_IP, &wifi_event_handler, NULL);

    wifi_config_t wifi_config = {
        .sta = {
            .ssid = EXAMPLE_ESP_WIFI_SSID,
            .password = EXAMPLE_ESP_WIFI_PASS,
            .threshold.authmode = WIFI_AUTH_WPA2_PSK,
        },
    };
    esp_netif_init();
    esp_netif_create_default_wifi_sta();
    wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT();
    esp_wifi_init(&cfg);
    esp_wifi_set_mode(WIFI_MODE_STA);
    esp_wifi_set_config(ESP_IF_WIFI_STA, &wifi_config);
    esp_wifi_start();
}

/*
 * @brief Event handler registered to receive MQTT events
 *
 *  This function is called by the MQTT client event loop.
 *
 * @param handler_args user data registered to the event.
 * @param base Event base for the handler(always MQTT Base in this example).
 * @param event_id The id for the received event.
 * @param event_data The data for the event, esp_mqtt_event_handle_t.
 */
static void mqtt_event_handler(void *handler_args, esp_event_base_t base, int32_t event_id, void *event_data)
{
    ESP_LOGD(TAG, "Event dispatched from event loop base=%s, event_id=%d", base, event_id);
    esp_mqtt_event_handle_t event = event_data;

    switch ((esp_mqtt_event_id_t)event_id)
    {
    case MQTT_EVENT_CONNECTED:
        ESP_LOGI(TAG, "MQTT_EVENT_CONNECTED");
        MQTT_CONNECTED = 1;
        break;

    case MQTT_EVENT_DISCONNECTED:
        ESP_LOGI(TAG, "MQTT_EVENT_DISCONNECTED");
        MQTT_CONNECTED = 0;
        break;

    case MQTT_EVENT_ERROR:
        ESP_LOGI(TAG, "MQTT_EVENT_ERROR");
        break;
    default:
        ESP_LOGI(TAG, "Other event id:%d", event->event_id);
        break;
    }
}

esp_mqtt_client_handle_t client = NULL;
static void mqtt_app_start(void)
{
    ESP_LOGI(TAG, "STARTING MQTT");
    esp_mqtt_client_config_t mqttConfig = {
        .uri = "mqtt://YOUR_RPI_IP_ADDRESS:1883"};

    client = esp_mqtt_client_init(&mqttConfig);
    esp_mqtt_client_register_event(client, ESP_EVENT_ANY_ID, mqtt_event_handler, client);
    esp_mqtt_client_start(client);
}

void Publisher_Task(void *pvParameters){
  ds18b20_init(DS_PIN);

  while (1) {
    ds18b20_requestTemperatures();

    float TempC = ds18b20_get_temp();
    printf("Temperature: %.2fC\n", TempC);
    char temperatureC[12];
    sprintf(temperatureC, "%.2f", TempC);

    float TempF = TempC*9/5 + 32;
    printf("Temperature: %.2fF\n", TempF);
    char temperatureF[12];
    sprintf(temperatureF, "%.2f", TempF);
    
    if (MQTT_CONNECTED){

		esp_mqtt_client_publish(client, MQTT_PUB_TEMPC_DS18B20, temperatureC, 0, 0, 0);
		esp_mqtt_client_publish(client, MQTT_PUB_TEMPF_DS18B20, temperatureF, 0, 0, 0);
        
		}	
  vTaskDelay(1000 / portTICK_PERIOD_MS);

  }
}
void app_main()
{
    nvs_flash_init();
    wifi_init();
    xTaskCreate(&Publisher_Task, "Publisher_Task", 2048, NULL, 5, NULL );
}

How the Code Works?

Firstly, we will start by including the necessary libraries that includes the gpio driver, ds18b20 library, FreeRTOS libraries to generate delays, esp_wifi.h to enable Wi-Fi connectivity, esp_event.h to monitor the Wi-Fi and MQTT events, mqtt_client.h to setup MQTT protocol for publish/subscribe and esp_log.h as the logging library.

#include <stdio.h>
#include <stdint.h>
#include <stddef.h>
#include <string.h>
#include "esp_wifi.h"
#include "esp_system.h"
#include "nvs_flash.h"
#include "esp_event.h"
#include "esp_netif.h"
#include "rom/ets_sys.h"
#include "driver/gpio.h"
#include "sdkconfig.h"

#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#include "freertos/queue.h"

#include "lwip/sockets.h"
#include "lwip/dns.h"
#include "lwip/netdb.h"

#include "esp_log.h"
#include "mqtt_client.h"
#include "ds18b20.h" 

The variable ‘DS_PIN’ holds the one wire GPIO number that will be used to connect with the data pin of the sensor. We are using GPIO4.

const int DS_PIN = 4;

This code uses Informational Logging. The log function takes in two arguments. The first argument is the tag and the second argument is a formatted string. Therefore this global variable will be useful while calling the ESP_LOGI() functions. Here, “MQTT_EXAMPLE” and is the tag that will be used while logging.

static const char *TAG = "MQTT_EXAMPLE";

Next, we have defined the parameters for the Wi-Fi SSID and password. Specify your own network credentials to successfully connect your ESP32 board with the Wi-Fi network.

#define  EXAMPLE_ESP_WIFI_SSID "YOUR_SSID"
#define  EXAMPLE_ESP_WIFI_PASS "YOUR_PASSWORD"

We will define some variables to monitor the Wi-Fi connection including the maximum retry value that is set as 10 and the retry count that initially holds the value 0.

#define MAX_RETRY 10
static int retry_cnt = 0;

After that we define the topics the ESP32 board will publish to. These include: esp32/ds18b20/temperatureC for temperature readings in degree Celsius and esp32/ds18b20/temperatureF for temperature readings in Fahrenheit.

#define MQTT_PUB_TEMPC_DS18B20 "esp32/ds18b20/temperatureC"
#define MQTT_PUB_TEMPF_DS18B20 "esp32/ds18b20/temperatureF"

Handling Wi-Fi Events

We have the wifi_event_handler() function which handles the Wi-Fi events. This acts as a callback function, when any Wi-Fi event occurs. There are a different events that the Wi-Fi driver posts to the event task. These include: SYSTEM_EVENT_STA_START, SYSTEM_EVENT_STA_CONNECTED, SYSTEM_EVENT_STA_GOT_IP and SYSTEM_EVENT_STA_DISCONNECTED. These events occur if Wi-Fi is connected, a station gets connected to the AP, Wi-Fi gets IP or if the station disconnects from the AP respectively.

In our wifi_event_handler() function, we will check if the Wi-Fi event id corresponds to either of these four events. If it does, then it will print a relevant message on the ESP-IDF according to the event type and call an appropriate function. If either SYSTEM_EVENT_STA_START event, the function esp_wifi_connect() will be called. This will be responsible for connecting the ESP32 Wi-Fi station to the access point. If the event SYSTEM_EVENT_STA_DISCONNECTED occurs, then the function esp_wifi_connect() will be called till the maximum retry value which we set as 10. If the Wi-Fi doesn’t connect within the number of tries, then the ESP-IDF terminal prints the message that the max retry failed. If SYSTEM_EVENT_STA_GOT_IP event occurs, then the function mqtt_app_start() will be called to initiate the MQTT client connection.

static esp_err_t wifi_event_handler(void *arg, esp_event_base_t event_base,
                                    int32_t event_id, void *event_data)
{
    switch (event_id)
    {
    case WIFI_EVENT_STA_START:
        esp_wifi_connect();
        ESP_LOGI(TAG, "Trying to connect with Wi-Fi\n");
        break;

    case WIFI_EVENT_STA_CONNECTED:
        ESP_LOGI(TAG, "Wi-Fi connected\n");
        break;

    case IP_EVENT_STA_GOT_IP:
        ESP_LOGI(TAG, "got ip: startibg MQTT Client\n");
        mqtt_app_start();
        break;

    case WIFI_EVENT_STA_DISCONNECTED:
        ESP_LOGI(TAG, "disconnected: Retrying Wi-Fi\n");
        if (retry_cnt++ < MAX_RETRY)
        {
            esp_wifi_connect();
        }
        else
            ESP_LOGI(TAG, "Max Retry Failed: Wi-Fi Connection\n");
        break;

    default:
        break;
    }
    return ESP_OK;
}

Initialize Wi-Fi

The wifi_init() function will be called inside the app_main() function to initialize Wi-Fi in station mode for ESP32.

void wifi_init(void)
{
    esp_event_loop_create_default();
    esp_event_handler_register(WIFI_EVENT, ESP_EVENT_ANY_ID, &wifi_event_handler, NULL);
    esp_event_handler_register(IP_EVENT, IP_EVENT_STA_GOT_IP, &wifi_event_handler, NULL);

    wifi_config_t wifi_config = {
        .sta = {
            .ssid = EXAMPLE_ESP_WIFI_SSID,
            .password = EXAMPLE_ESP_WIFI_PASS,
            .threshold.authmode = WIFI_AUTH_WPA2_PSK,
        },
    };
    esp_netif_init();
    esp_netif_create_default_wifi_sta();
    wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT();
    esp_wifi_init(&cfg);
    esp_wifi_set_mode(WIFI_MODE_STA);
    esp_wifi_set_config(ESP_IF_WIFI_STA, &wifi_config);
    esp_wifi_start();
}

We start off by creating the default event loop by calling the function esp_event_loop_create_default(). Afterwards, we use esp_event_handler_register() to register event handlers to the system event loop for both the WIFI_EVENT and IP_EVENT.

    esp_event_loop_create_default();
    esp_event_handler_register(WIFI_EVENT, ESP_EVENT_ANY_ID, &wifi_event_handler, NULL);
    esp_event_handler_register(IP_EVENT, IP_EVENT_STA_GOT_IP, &wifi_event_handler, NULL);

In this part, we set up the SSID and password of the network we want our ESP32 to connect with, as well as assign the security setting.

  wifi_config_t wifi_config = {
        .sta = {
            .ssid = EXAMPLE_ESP_WIFI_SSID,
            .password = EXAMPLE_ESP_WIFI_PASS,
	     .threshold.authmode = WIFI_AUTH_WPA2_PSK,
        },
    };

Here we are initializing lwIP through the function esp_netif_init() and create an IwIP task which is also known as a TCP/IP task. lwIP is a TCP/IP library stack provided by ESP-IDF that is used to perform various protocols such as TCP, UDP, DHCP etc.

esp_netif_init();

The following line is used for Wi-Fi default initialization for station mode. This API is used to initialize as well as register event handlers for the default interface which is station in our case. It creates a network interface instance binding Wi-Fi driver and TCP/IP stack. When a station is in the process of connecting to an AP, various processes automatically get handled through this function.

esp_netif_create_default_wifi_sta();

Then we initialize the Wi-Fi allocate resource for the Wi-Fi driver. It is responsible for initiating the Wi-Fi task. It takes in a single parameter cfg which is a pointer to the already initialized Wi-Fi configuration structure which is set to WIFI_INIT_CONFIG_DEFAULT() so that the initialization of the configuration is at default values. Here wifi_init_config_t is a structure that denotes the Wi-Fi stack configuration parameters that are passed inside the esp_wifi_init() function.

wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT();
 esp_wifi_init(&cfg);

Moreover, we set Wi-Fi mode as station. To set the Wi-Fi mode as station, we use the function esp_wifi_set_mode() and pass the WiFI_MODE_STA as a parameter inside it.

esp_wifi_set_mode(WIFI_MODE_STA);

Then we assign our network’s SSID and password. This way the Wi-Fi driver gets configured with the AP network credentials and Wi-Fi mode. Then, we start the Wi-Fi connection at our assigned configuration.

esp_wifi_set_config(ESP_IF_WIFI_STA, &wifi_config);
esp_wifi_start();

Handling MQTT Events

Next, we have the mqtt_event_handler() function which handles the MQTT events. This function is called by the MQTT client event loop. We will check if the event id corresponds to either of the three events which can be MQTT_EVENT_CONNECTED, MQTT_EVENT_DISCONNECTED or MQTT_EVENT_ERROR. If it does, then it will print a relevant message on the ESP-IDF according to the event type and call an appropriate function.

The table below shows the descriptions of the MQTT events that will be used in this example.

MQTT_EVENT_CONNECTEDThis event is posted when the client successfully connects to the broker and is ready to send/receive data.
MQTT_EVENT_DISCONNECTEDThis event is posted when the client cancels the connection between the broker as the server is not available. The client is not able to send/receive data in this scenario.
MQTT_EVENT_ERRORThis events gets posted by the client when it experiences an error.
static void mqtt_event_handler(void *handler_args, esp_event_base_t base, int32_t event_id, void *event_data)
{
    ESP_LOGD(TAG, "Event dispatched from event loop base=%s, event_id=%d", base, event_id);
    esp_mqtt_event_handle_t event = event_data;

    switch ((esp_mqtt_event_id_t)event_id)
    {
    case MQTT_EVENT_CONNECTED:
        ESP_LOGI(TAG, "MQTT_EVENT_CONNECTED");
        MQTT_CONNECTED = 1;
        break;

    case MQTT_EVENT_DISCONNECTED:
        ESP_LOGI(TAG, "MQTT_EVENT_DISCONNECTED");
        MQTT_CONNECTED = 0;
        break;

    case MQTT_EVENT_ERROR:
        ESP_LOGI(TAG, "MQTT_EVENT_ERROR");
        break;
    default:
        ESP_LOGI(TAG, "Other event id:%d", event->event_id);
        break;
    }
}

If the event MQTT_EVENT_CONNECTED is posted by the client, the “MQTT_CONNECTED” variable is set to the value 1, which initially held the value 0.

case MQTT_EVENT_CONNECTED:
        ESP_LOGI(TAG, "MQTT_EVENT_CONNECTED");
        MQTT_CONNEECTED = 1;
        break;

If the event MQTT_EVENT_DISCONNECTED is posted by the client, the MQTT_CONNECTED variable is set to the value 0 and the terminal prints the message indicating that this event occurred. Similarly, for the rest of the events a relevant message is printed on the terminal along with the event_id incase of a different event.

case MQTT_EVENT_DISCONNECTED:
        ESP_LOGI(TAG, "MQTT_EVENT_DISCONNECTED");
        MQTT_CONNEECTED = 0;
        break;

    case MQTT_EVENT_ERROR:
        ESP_LOGI(TAG, "MQTT_EVENT_ERROR");
        break;
    default:
        ESP_LOGI(TAG, "Other event id:%d", event->event_id);
        break;

mqtt_app_start()

Inside the mqtt_app_start() function, an MQTT client handle is created according to the configuration parameters set using esp_mqtt_client_init(). This function takes in a single parameter which is the pointer to the MQTT configuration structure. The MQTT configuration structure holds the MQTT Broker IP address which acts as the mqtt server. Make sure to specify the IP address of your Raspberry Pi which has Mosquitto broker running on it, inside the MQTT configuration structure.

After that we will call the function esp_mqtt_client_register_event() which is used to register the MQTT event. It takes in four parameters. The first parameter is the MQTT client handle. The second parameter is the event type. The third parameter is the handler callback and the last parameter is the handle context which is mqtt_client_handle, ‘client’ in our case. Finally, we will start the MQTT client using the function esp_mqtt_client_start() and specify the already created client handle as a parameter inside it.

esp_mqtt_client_handle_t client = NULL;
static void mqtt_app_start(void)
{
    ESP_LOGI(TAG, "STARTING MQTT");
    esp_mqtt_client_config_t mqttConfig = {
        .uri = "mqtt://YOUR_RPI_IP_ADDRESS:1883"};
    
    client = esp_mqtt_client_init(&mqttConfig);
    esp_mqtt_client_register_event(client, ESP_EVENT_ANY_ID, mqtt_event_handler, client);
    esp_mqtt_client_start(client);
}

Publisher_Task()

Inside the Publisher_Task() function, the DS18B20 sensor is initialized and the sensor data is acquired. It is then published to the corresponding topics after every second using MQTT protocol.

void Publisher_Task(void *pvParameters){
  ds18b20_init(DS_PIN);

  while (1) {
    ds18b20_requestTemperatures();

    float TempC = ds18b20_get_temp();
    printf("Temperature: %.2fC\n", TempC);
    char temperatureC[12];
    sprintf(temperatureC, "%.2f", TempC);

    float TempF = TempC*9/5 + 32;
    printf("Temperature: %.2fF\n", TempF);
    char temperatureF[12];
    sprintf(temperatureF, "%.2f", TempF);
    
    if (MQTT_CONNECTED){

		esp_mqtt_client_publish(client, MQTT_PUB_TEMPC_DS18B20, temperatureC, 0, 0, 0);
		esp_mqtt_client_publish(client, MQTT_PUB_TEMPF_DS18B20, temperatureF, 0, 0, 0);
        
		}	
  vTaskDelay(1000 / portTICK_PERIOD_MS);

  }
}

We first initialize the DS18B20 sensor by using ds18b20_init() function and pass the one wire GPIO pin as a parameter inside it.

ds18b20_init(DS_PIN);

Inside the infinite while loop, we will start acquiring the DS18B20 sensor readings by first requesting the temperatures using ds18b20_requestTemperatures(). Then, we will obtain the temperature reading in degree Celsius using the function ds18b20_get_temp(). This function returns the temperature reading as a float data type. We will first convert the float data type to an array of characters and round off to two decimal places. Similarly, we will convert the temperature reading in degree Celsius to degree Fahrenheit as well by multiplying it with 9/5 and adding 32 to it. Both the readings are continuously read after a delay of every second and printed on the ESP-IDF terminal.

If MQTT_CONNECTED is true, then the sensor readings will get published to the corresponding topics every second.

while (1) {
    ds18b20_requestTemperatures();

    float TempC = ds18b20_get_temp();
    printf("Temperature: %.2fC\n", TempC);
    char temperatureC[12];
    sprintf(temperatureC, "%.2f", TempC);

    float TempF = TempC*9/5 + 32;
    printf("Temperature: %.2fF\n", TempF);
    char temperatureF[12];
    sprintf(temperatureF, "%.2f", TempF);
    
    if (MQTT_CONNECTED){

   esp_mqtt_client_publish(client, MQTT_PUB_TEMPC_DS18B20, temperatureC, 0, 0, 0);
   esp_mqtt_client_publish(client, MQTT_PUB_TEMPF_DS18B20, temperatureF, 0, 0, 0);
    
}	
  vTaskDelay(1000 / portTICK_PERIOD_MS);

  }

app_main()

Inside the app_main() function, first NVS is initialized by calling the nvs_flash_init() function. Then, wifi_init() function is called which will initialize Wi-Fi in station mode for ESP32. After that, we use xTaskCreate() to create the Publisher_Task that will publish the sensor readings on the corresponding topics after every second.

void app_main()
{
    nvs_flash_init();
    wifi_init();
    xTaskCreate(&Publisher_Task, "Publisher_Task", 2048, NULL, 5, NULL );
}

Compiling the Sketch

To flash your chip, type the following command in the serial terminal. Remember to replace the COM port with the one through which your board is connected.

idf.py -p COMX flash monitor

After the code is successfully flashed, you can view different messages on the ESP-IDF terminal. First, the Wi-Fi gets successfully connected and then the MQTT connection is established. You can also view the DS18B20 sensor readings continuously updating on the terminal.

ESP-IDF MQTT DS18B20 Readings with Node-Red Terminal

Now let us set up our Node-Red dashboard to view the sensor data.

Node-Red Dashboard as MQTT DS18B20 Readings Subscriber

Our ESP32 publisher is sending the individual DS18B20 readings to the specific topics after every second. In this section, we will show you how to setup Node-Red as an MQTT subscriber to our ESP32 DS18B20 topics. By using Node-Red dashboard, we will be able to view the sensor readings on our smart phone/laptop/computer. Lets first learn how to build the dashboard.

You can use any other MQTT subscription service as well to subscribe to the MQTT topics such as MQTTx Desktop Client which we previously used.

Refer to the getting started guide with Node-Red on Raspberry Pi:

To access Node-RED, we require the IP address of our Raspberry Pi and the port number on which Node-RED is accessible. By default, it starts on port 1880. Open any web browser and enter the IP address of your Raspberry Pi followed by the port number.

For example:

192.168.18.8:1880

Create Flow

This will open the Node-RED interface. Now we will start creating the flow.

ESP-IDF MQTT BME280 with Node-Red Create flow 1

Go to the right side and find dashboard. Install the dashboard if it isn’t already installed.

ESP-IDF MQTT BME280 with Node-Red Create flow 2

Click ‘Dashboard’ to open its tab. Now we create the dashboard tab node. To create a new tab, go to the Dashboard tab and click +tab. Give a name according to your preference and an icon available from the list of links given below:

After that, click Update to save the changes.

We has created one tab named Home and using icons from Angular Material Icons.

ESP-IDF MQTT BME280 with Node-Red Edit Dashboard Tab Node

Next we will add the widgets. We will add one group to the tab for the sensor. To create a group, click +group in the tab.

We have named the group as ‘DS18B20 Readings.’

ESP-IDF MQTT DS18B20 Readings with Node-Red Edit dashboard group node

Now let us add the widgets to our group. To display the temperature readings, we will choose gauges. Go to the Nodes section found at the far left and scroll down to find the required nodes under Dashboard.

Drag and drop two gauges and two mqtt in nodes to the flow as shown below:

ESP-IDF MQTT DS18B20 Readings with Node-Red Add Widgets

Let us edit the properties of the nodes now. Click the first mqtt in node. This opens its properties. For the server (MQTT Broker), which is Mosquitto Broker on Raspberry Pi, set it to localhost:1883. Add the name of the topic to be subscribed, specify the qos and then click the Done button.

This particular node is subscribed to the topic ‘esp32/ds18b20/temperatureC.’

ESP-IDF MQTT DS18B20 Readings with Node-Red Edit mqtt in node 1

Likewise, edit the properties of the second mqtt in node. This particular node is subscribed to the topic ‘esp32/ds18b20/temperatureF.’

ESP-IDF MQTT DS18B20 Readings with Node-Red Edit mqtt in node 2

Edit the properties of the first and second gauge as shown below:

Join the nodes as shown below. Then, click the Deploy button at the top.

ESP-IDF MQTT DS18B20 Readings with Node-Red connect nodes and deploy

The status of the MQTT in nodes changes to ‘connected.’

ESP-IDF MQTT DS18B20 Readings with Node-Red Nodes Connected

To open the dashboard, type: http://Your_RPI_IP_address:1880/ui in a new web browser and press enter. The user interface will open showing the two gauges with readings from the DS18B20 sensor.

ESP-IDF MQTT DS18B20 Readings with Node-Red Dashboard Laptop View

This is how the Node-Red Dashboard looks like when viewed from a smart phone.

ESP-IDF MQTT DS18B20 Readings with Node-Red Dashboard Mobile View

You may also like to read:

If you are using Arduino IDE instead of ESP-IDF, you can read these:

Leave a Comment