Skip to content

Commit

Permalink
Merge branch 'example-i2c-address-change' into 'master'
Browse files Browse the repository at this point in the history
add example to change I2C address for SLF3x

See merge request MSO-SW/drivers/arduino/arduino-i2c-sf06-lf!5
  • Loading branch information
LeonieFierz committed Apr 26, 2024
2 parents d025993 + 998ab96 commit 6a6892e
Show file tree
Hide file tree
Showing 7 changed files with 339 additions and 4 deletions.
4 changes: 4 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,10 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0

## [Unreleased]

### Added
Example how to change I2C address for SLF3x sensors

### Changed
Names of defines for I2C addresses in SensirionI2cSf06Lf.h changed

## [0.1.0] - 2022-03-30
Expand Down
6 changes: 2 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@ support it are listed in the API description.
|[LD20-0600L](https://sensirion.com/products/catalog/LD20-0600L/)| **0x08**|
|[LD20-2600B](https://sensirion.com/products/catalog/LD20-2600B/)| **0x08**|

The following instructions and examples use a *SLF3C-1300F*.

For instructions how to change the I2C address of your SLF3x sensor please refer to `examples/exampleI2cAddressChange/README.md`.

The following instructions and examples use a *SLF3C-1300F*.

## Installation of the library

Expand Down Expand Up @@ -67,8 +67,6 @@ Use the following pin description to connect your SF06-LF to the standard I²C b
| 6 | | NC | Do not connect |




The recommended voltage is 3.3V.

### Board specific wiring
Expand Down
68 changes: 68 additions & 0 deletions examples/exampleI2cAddressChange/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
# How to change I²C Address for SLF3x Sensor

In a setup where you want to attach more than one SLF3x Sensor to the same I²C Bus you have two options. You can use a multiplexer or you change the I²C address of the attached sensors.

This example explains how you can change the I²C address of your SLF3x sensor and subsequently reading out measurements from both sensors. Note that the address change is not permanent, meaning that the sensor is set back to its default address after a soft reset (specific I2C command) or hard reset (power cycle).

## Setup instructions

The example is set up with an ESP32 DevKitC board and two SLF1300-F sensors attached.

### Sensor wiring

Use the following pin description to connect your SLF3x to the standard I²C bus of your Arduino board:

<img src="../../images/SLF3x_Pinout_IRQn.png" width="300px">

Connect both sensor the your ESP32 Board following the table below.

| *SLF3x* | *SLF3x Pin* | *Cable Color* | *Board Pin* | *Comments* |
| :---: | --- | --- | --- | --- |
| IRQn| 1 | purple | GPIO 2 / GPIO 4 | Connect IRQn pin of each sensor to its own GPIO pin on the board
| SDA | 2 | green | GPIO 21 | Connect SDA pins of all sensors to GPIO21 on the board
| VDD | 3 | red | 3V3 |
| GND | 4 | black | GND |
| SCL | 5 | yellow | GPIO 22 | Connect SCL pins of all sensors to GPIO22 on the board

<img src="../../images/esp32-devkitc-i2c-pinout-3.3V-IRQn.png" width="300px">

To be able to connect the SDA, SCL, VDD and GND of both
sensors to the same pin on the ESP32 Board, you can for example use a Breadboard and wire the sensors as shown below.

<img src="../../images/wiring-i2c-address-change-example.png" width="300px">

### Adapt and run example code

* Open the example `exampleI2cAddressChange.ino` in Arduino IDE
* Check that the defines for the IRQn pins match with wiring, for the wiring exaplained above it should be
* `#define IRQN_PIN_SENSOR_A 4`
* `#define IRQN_PIN_SENSOR_B 2`
* You can change the I²C address to use by changing the following lines. You can use any valid I²C address in the range of 0x0 to 0x7F.
* `#define I2C_ADDR_SENSOR_A 0x0A`
* `#define I2C_ADDR_SENSOR_B 0x0B`
* Compile and run the example
* If everything worked out well, you will get measurement readings for both sensors attached on the serial output (use Baudrate of 115200)

<details><summary>Detailed Address Change Sequence</summary>
<p>

1. Send I2C Address change command to default sensor address 0x08. This command is recieved by all SLF3x sensors on the bus still having the default address.
2. Select the sensor which should accept the new I2C address sent in step 1 by sending a high pulse of at least 150μs to its IRQn Pin.
* To do so, set the GPIO Pin of the board where the IRQn Pin of the sensor is connected to output mode and set it to a high state for at least 150μs.
* The sensor waits for such a pulse on the IRQn Pin for 1.5ms after the I2C address change command has been sent.
3. Change the GPIO Pin back to low state and switch it to INPUT mode. You might want to configure it with a pulldown to avoid unintended high state.
4. Wait until 1.5ms have elapsed after sending the I2C address change command.
5. Read out the GPIO Pin, which should be set to high state for 200μs if the sensor changed its I2C address successfully.

</p>
</details>


## Limitations

- The feature is only supported by SLF3x sensors with a serial number above 22xxxxxxxx.
- After a soft or hard reset the I²C address is set back to the default address 0x08. A soft reset is triggered by a speical I2C command, see `i2c_soft_reset()` in the example, and a hard reset is triggered by a power cylce of the sensor.

## Further readings

[Application note SLF3x I2C Address change](https://www.sensirion.com/media/documents/15D8B73E/6614FAE3/LQ_AN_SLF3x-I2C-Address-change.pdf)
265 changes: 265 additions & 0 deletions examples/exampleI2cAddressChange/exampleI2cAddressChange.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,265 @@
/*
* Copyright (c) 2023, Sensirion AG
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this
* list of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* * Neither the name of Sensirion AG nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include <Arduino.h>
#include <SensirionI2cSf06Lf.h>
#include <Wire.h>

// GPIO pins to which the IRQn pin of your sensors are connected
#define IRQN_PIN_SENSOR_A 4
#define IRQN_PIN_SENSOR_B 2

// I2C addresses to use for the sensors
#define I2C_ADDR_SENSOR_A 0x0A
#define I2C_ADDR_SENSOR_B 0x0B

// Define the sensor objects used for sensor communication after the address
// change
SensirionI2cSf06Lf sensorA;
SensirionI2cSf06Lf sensorB;

static char errorMessage[64];
static int16_t error;

void print_byte_array(uint8_t* array, uint16_t len) {
uint16_t i = 0;
Serial.print("0x");
for (; i < len; i++) {
Serial.print(array[i], HEX);
}
}

/**
* Perform soft reset for all sensor connected to I2C Bus.
*/
void i2c_soft_reset() {
Wire.beginTransmission(0x00);
size_t writtenBytes = Wire.write(0x06);
uint8_t i2c_error = Wire.endTransmission();
}

/**
* @brief Change the I2C address of the sensor.
*
* @details If you have more then one SLF3x sensor
* connected to the same I2C bus you need to configure the sensor addresses as
* all of them have the same default address.
* Preconditions to call this method:
* * Your sensor needs to be resetted (hard or soft reset, no commands sent
* after the reset)
* * PIN1 of the sensor for which you want to change the address must be
* connected to a GPIO pin
* * Note that only sensors with a serial number above 22xxxxxxxx have the IRQn
* pin
*
* @note The I2C address is not configured permanently, you need to run the
* procedure after each restart of the sensor
* (hard or soft reset depending on your sensor model).
*
* @param newI2cAddress the I2C address that shall be assigned to your sensor
* @param sensorIrqPin GPIO pin number to which you have IRQn Pin (Pin nr 1) of
* the sensor connected
* @return error_code 0 on success, an error code otherwise (-1 if the
* confirmation pulse from the sensor could not be read)
*/
int16_t changeSensorAddress(TwoWire& wire, uint16_t newI2cAddress,
uint8_t sensorIrqPin) {
uint8_t communication_buffer[5] = {0};
int16_t localError = NO_ERROR;
uint8_t* buffer_ptr = communication_buffer;

// Send I2C address change command 0x3661 with the new I2C address as a
// parameter (including CRC for the parameter)
SensirionI2CTxFrame txFrame =
SensirionI2CTxFrame::createWithUInt16Command(0x3661, buffer_ptr, 5);
txFrame.addUInt16(newI2cAddress);
// Note that the command is sent to the default address 0x08 of the sensor
localError = SensirionI2CCommunication::sendFrame(SLF3C_1300F_I2C_ADDR_08,
txFrame, wire);
if (localError != NO_ERROR) {
Serial.println("error sending address change command");
errorToString(localError, errorMessage, sizeof errorMessage);
Serial.println(errorMessage);
Serial.println(
"As there are multiple sensors attached initially listening on the same I2C address \
the acknowledge might overlap and cause an error which you can ignore if the subsequent communication is successful.");
}

// set IRQN pin of one sensor to high for at least 150μs to confirm address
// change only after this pulse has been sent the sensor actually accepts
// the new I2C address sent before
pinMode(sensorIrqPin, OUTPUT);
digitalWrite(sensorIrqPin, HIGH);
delayMicroseconds(500);
// reset IRQn pin back to low state
digitalWrite(sensorIrqPin, LOW);

// switch mode to input and listen to the pulse the sensor
// sends 1500μs after the address change command to confirm the new I2C
// address
pinMode(sensorIrqPin, INPUT_PULLDOWN);
delayMicroseconds(500);
uint8_t success = 0;
uint16_t cnt = 0;
while (success == 0 && cnt < 100) {
cnt++;
success = digitalRead(sensorIrqPin);
delayMicroseconds(10);
}
if (success == 0) {
// return error as sensor did not acknowledge address change
return -1;
}

Serial.print("Sensor address changed to: 0x");
if (newI2cAddress < 16) {
Serial.print("0");
}
Serial.println(newI2cAddress, HEX);
return NO_ERROR;
}

void readAndPrintSerial(SensirionI2cSf06Lf& sensor) {
uint32_t productIdentifier = 0;
uint8_t serialNumber[8] = {0};
error = sensor.readProductIdentifier(productIdentifier, serialNumber, 8);
if (error != NO_ERROR) {
Serial.print("Error trying to execute readProductIdentifier(): ");
errorToString(error, errorMessage, sizeof errorMessage);
Serial.println(errorMessage);
return;
}
Serial.print("productIdentifier: ");
Serial.print(productIdentifier);
Serial.print("\t");
Serial.print("serialNumber: ");
print_byte_array(serialNumber, 8);
Serial.println();
}

void readAndPrintMeasurement(SensirionI2cSf06Lf& sensor) {
float aFlow = 0.0;
float aTemperature = 0.0;
uint16_t aSignalingFlags = 0u;
error = sensor.readMeasurementData(INV_FLOW_SCALE_FACTORS_SLF3C_1300F,
aFlow, aTemperature, aSignalingFlags);
if (error != NO_ERROR) {
Serial.print("Error trying to execute readMeasurementData(): ");
errorToString(error, errorMessage, sizeof errorMessage);
Serial.println(errorMessage);
return;
}
Serial.print("aFlow: ");
Serial.print(aFlow);
Serial.print("\t");
Serial.print("aTemperature: ");
Serial.print(aTemperature);
Serial.print("\t");
Serial.print("aSignalingFlags: ");
Serial.print(aSignalingFlags);
Serial.println();
}

void setup() {
error = NO_ERROR;

Serial.begin(115200);
while (!Serial) {
delay(100);
}

Wire.begin();

// Make sure that sensors are in proper state to perform a address change by
// doing a soft reset and not sending any other commands prior to the
// address change procedure
i2c_soft_reset();
// SLF3x sensors need 25ms to start up after the reset
delay(25);

// Change address of the first sensor
// Set IRQN_PIN_SENSOR_A to the GPIO pin number where you connected Pin 1
// of your first sensor.
error = changeSensorAddress(Wire, I2C_ADDR_SENSOR_A, IRQN_PIN_SENSOR_A);
if (error != NO_ERROR) {
Serial.print("Error changing sensor address: ");
errorToString(error, errorMessage, sizeof errorMessage);
Serial.println(errorMessage);
return;
}

// Change address of the first sensor
// Set IRQN_PIN_SENSOR_B to the GPIO pin number where you connected Pin 1
// of your second sensor.
error = changeSensorAddress(Wire, I2C_ADDR_SENSOR_B, IRQN_PIN_SENSOR_B);
if (error != NO_ERROR) {
Serial.print("Error changing sensor address: ");
errorToString(error, errorMessage, sizeof errorMessage);
Serial.println(errorMessage);
return;
}

// Initialize first sensor
Serial.println("Initialising sensor A");
sensorA.begin(Wire, 0x0A);
readAndPrintSerial(sensorA);
error = sensorA.startH2oContinuousMeasurement();
if (error != NO_ERROR) {
Serial.print("Error trying to execute startH2oContinuousMeasurement() "
"for sensor A: ");
errorToString(error, errorMessage, sizeof errorMessage);
Serial.println(errorMessage);
return;
}

// Initialize second sensor
Serial.println("Initialising sensor B");
sensorB.begin(Wire, 0x0B);
readAndPrintSerial(sensorB);
error = sensorB.startH2oContinuousMeasurement();
if (error != NO_ERROR) {
Serial.print("Error trying to execute startH2oContinuousMeasurement() "
"for sensor B: ");
errorToString(error, errorMessage, sizeof errorMessage);
Serial.println(errorMessage);
return;
}
}

void loop() {
delay(20);
// Read out measurements for first sensor
Serial.print("sensor A - ");
readAndPrintMeasurement(sensorA);
// Read out measurements for second sensor
Serial.print("sensor B - ");
readAndPrintMeasurement(sensorB);
}
Binary file added images/SLF3x_Pinout_IRQn.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added images/esp32-devkitc-i2c-pinout-3.3V-IRQn.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added images/wiring-i2c-address-change-example.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.

0 comments on commit 6a6892e

Please sign in to comment.