ESP32-SI7021 humidity and temperature sensor

General Description

The module is responsible for handling sensors: temperature, humidity and optionally a force sensor and integration with ROS2. It is based on the micro-ROS module, which was developed within the European OFERA project. This project contains source code for an ESP32 microcontroller that allows you to read temperature and humidity from a sensor using the I2C interface. A micro-ROS node is running on the microcontroller and sends the values received from the sensor to a micro-ROS Agent running on a PC.

Resource Link
Source code https://gitc.piap.lukasiewicz.gov.pl/ai-prism/wp3/ros-framework/base_hardware/micro-ros-esp32-sensors.git
Demo Video https://gitc.piap.lukasiewicz.gov.pl/ai-prism/reference-architecture/docs/guides/video/vigo_pilot.mp4

Contact

The following table includes contact information of the main developers in charge of the component:

Name email Organisation
Jan Kaniuka jan.kaniuka@piap.lukasiewicz.gov.pl logo image

License

Apache-2.0 license

Technical Foundations

Architecture

architecture

Source

ROS interfaces

Type Topic name Message type Description
Topic (publisher) /ai_prism/humidity std_msgs/Float32 Humidity (measuring range: 0% RH to 80% RH, accuracy: ± 3% RH)
Topic (publisher) /ai_prism/temperature std_msgs/Float32 Temperature (measuring range: -10 to 85°C, accuracy: ± 0.4°C)
Topic (publisher) /ai_prism/force std_msgs/Float32 Mock-up (a fixed value of 0.1 is published for now)

*All messages above are being published every 1 second.

Hardware

Connections

Si7021 ESP32
CL SCL (IO22)
DA SDA (IO21)
+ 3V3
- GND

Usage manual/deployment

  1. Connect ESP32 via micro-USB to your host PC.
  2. Start micro-ROS Agent on your PC using the command below. Remember to adjust --dev parameter - typically it's /dev/ttyUSB0. bash docker run -it --rm -v /dev:/dev --privileged --net=host microros/micro-ros-agent:jazzy serial --dev <usb_port>

    [!IMPORTANT] ESP32 will try to connect to the micro-ROS Agent for 60 seconds after connecting power.

Development enviroment setup

  1. Install the ESP-IDF as VSCode Extension using this manual. Choose Express setup mode during installation.
  2. Add yourself to dialout group.
  3. Follow the steps below: bash mkdir ai_prism && cd ai_prism/ git clone ssh://git@gitc.piap.lukasiewicz.gov.pl:777/ai-prism/wp3/ros-framework/base_hardware/micro-ros-esp32-sensors.git cd micro-ros-esp32-sensors/ai_prism_esp32 source ~/esp/v5.3.1/esp-idf/export.sh pip3 install catkin_pkg lark-parser colcon-common-extensions empy==3.3.4 idf.py set-target esp32 idf.py build flash
  4. On host PC run micro-ROS agent in Docker. bash docker run -it --rm -v /dev:/dev --privileged --net=host microros/micro-ros-agent:jazzy serial --dev <usb_port> -v6

Integrated and Open Source Components

It is based on the micro-ROS project: https://github.com/micro-ROS/micro_ros_espidf_component

License

Apache-2.0 license

How to install

TBD

How to use

Described above.