You dont have javascript enabled! Please enable it!

Practical case: Arduino MKR WAN 1310 LoRaWAN water level

Practical case: Arduino MKR WAN 1310 LoRaWAN water level — hero

Objective and use case

What you’ll build: This project involves creating a LoRa water level telemetry system using the Arduino MKR WAN 1310, JSN-SR04T ultrasonic sensor, and INA219 power monitor for real-time water level monitoring.

Why it matters / Use cases

  • Remote monitoring of water levels in agricultural fields to optimize irrigation schedules.
  • Real-time water level tracking in reservoirs to prevent overflow and manage water resources effectively.
  • Deployment in flood-prone areas for early warning systems to alert communities of rising water levels.
  • Integration with smart city infrastructure for enhanced urban water management.

Expected outcome

  • Real-time transmission of water level data with latencies under 5 seconds.
  • Power consumption metrics reported by INA219, aiming for less than 50mA during active sensing.
  • Accurate water level measurements with a resolution of 1 cm, transmitted via LoRaWAN.
  • Successful data reception at a distance of up to 10 km in rural environments.

Audience: Engineers and developers interested in IoT applications; Level: Intermediate

Architecture/flow: Arduino MKR WAN 1310 collects data from JSN-SR04T, processes it, and sends it via LoRaWAN, while INA219 monitors power usage.

Advanced Practical Case: LoRa Water Level Telemetry with Arduino MKR WAN 1310 + JSN-SR04T + INA219

This hands-on build turns an Arduino MKR WAN 1310 into a robust LoRaWAN water-level telemetry node. It uses a waterproof ultrasonic sensor (JSN-SR04T) to measure distance to the water surface, converts that to level/volume, and transmits metrics via LoRaWAN. An INA219 current/power monitor is added to report sensor/system power usage for field diagnostics. You will compile and flash the sketch using Arduino CLI, not the GUI, with a clean, reproducible command sequence.

The project is engineered for real-world deployment: it includes filtering, calibration, low-power sleep, and a compact binary payload with a working decoder snippet for The Things Stack (TTS/TTN).

Device model: Arduino MKR WAN 1310 + JSN-SR04T + INA219
Objective: lora-water-level-telemetry


Prerequisites

  • Operating system: Linux/macOS/Windows (64-bit)
  • Installed tools:
  • Arduino CLI 0.34.2 or newer
  • Bash/PowerShell to run commands
  • A serial terminal (Arduino CLI monitor or screen)
  • LoRaWAN network access (e.g., The Things Stack Community or Enterprise)
  • An application and an OTAA device with JoinEUI/AppEUI and AppKey
  • Correct frequency plan/region for your deployment (e.g., EU868, US915)
  • Basic familiarity with:
  • Arduino pin I/O and I2C
  • LoRaWAN concepts: OTAA join, ADR, data rate
  • Safety handling for 5V signals on 3.3V MCUs (level shifting)

Driver notes:
– Arduino MKR WAN 1310 uses native USB (CDC). On Windows, install the “Arduino SAMD Boards” driver when prompted or via the Arduino IDE package if needed. No CP210x/CH34x drivers are required.


Materials (Exact Models)

  • 1x Arduino MKR WAN 1310 (exact model)
  • 1x JSN-SR04T waterproof ultrasonic distance sensor (v2 or v3; TTL variant)
  • 1x INA219 DC current/power monitor (Adafruit or equivalent breakout; default I2C address 0x40)
  • 1x 3.7V LiPo battery (optional but recommended for field)
  • 1x 5V source from MKR WAN 1310 5V pin (provided by USB/VIN; used to power JSN-SR04T)
  • Resistors for level shifting JSN-SR04T Echo line (exact values):
  • R1 = 10 kΩ (series from sensor Echo to MCU input node)
  • R2 = 20 kΩ (from MCU input node to GND)
  • Dupont wires and a small breadboard or terminal blocks
  • Outdoor-rated enclosure with cable glands (optional but recommended)
  • Antenna for the MKR WAN 1310’s LoRa radio (as supplied with the board)

Library versions (tested):
– arduino:samd core 1.8.13
– MKRWAN library 1.1.0
– ArduinoLowPower 1.2.2
– Adafruit INA219 1.2.1

Note: If your environment provides newer versions, they should still work; pinning these ensures reproducibility.


Setup/Connection

The MKR WAN 1310 is a 3.3V logic microcontroller. The JSN-SR04T requires 5V power and outputs a 5V Echo pulse. Do not connect the 5V Echo directly to the MKR pin. Use the resistor divider below.

Pin Planning

  • JSN-SR04T
  • VCC: 5V (from MKR 5V pin)
  • GND: GND
  • TRIG: MKR pin D6 (3.3V output is fine)
  • ECHO: MKR pin D7 via R1/R2 divider (5V to ~3.3V)
  • INA219 (I2C)
  • VIN+: 5V source side (from MKR 5V pin)
  • VIN-: Load side to JSN-SR04T VCC
  • SDA: MKR SDA (pin labeled SDA)
  • SCL: MKR SCL (pin labeled SCL)
  • GND: MKR GND
  • VCC: 3.3V (preferred) or 5V; Adafruit INA219 supports 3.3V logic, so tie to 3.3V for clean logic levels

Electrical Connections Table

Component Pin/Label Connects To Notes
MKR WAN 1310 5V INA219 VIN+ 5V supply path to sensor via INA219 shunt
INA219 VIN- JSN-SR04T VCC Measures current/power of the ultrasonic sensor
MKR WAN 1310 GND INA219 GND, JSN-SR04T GND Common ground
MKR WAN 1310 3.3V INA219 VCC Power the INA219 logic at 3.3V
MKR WAN 1310 SDA INA219 SDA I2C data
MKR WAN 1310 SCL INA219 SCL I2C clock
MKR WAN 1310 D6 JSN-SR04T TRIG Trigger output to sensor
MKR WAN 1310 D7 JSN-SR04T ECHO via divider R1=10 kΩ from ECHO to D7 node; R2=20 kΩ from D7 node to GND; ensures ~3.3V at the MCU

Important:
– Place the INA219 shunt in series only with the JSN-SR04T VCC line; this allows measuring the sensor’s consumption without interfering with the MKR’s own power path.
– Ensure the MKR’s antenna is attached and outside any metal enclosure before joining the network.
– Keep the JSN-SR04T face unobstructed and at least 20 cm from walls for accurate readings.


Full Code

We will use a small project layout:

  • project folder: lora-water-level-telemetry/
  • lora-water-level-telemetry.ino (main)
  • secrets.h (your LoRaWAN keys; not committed)

The payload format:
– Byte 0..1: distance_mm (uint16, 0–65535)
– Byte 2..3: bus_mV (uint16, INA219 bus voltage in millivolts)
– Byte 4..5: current_mA_x10 (uint16, INA219 current in 0.1 mA units)
– Byte 6..7: volume_liters (uint16, computed volume; 1 L resolution)
– Byte 8: level_percent (uint8, 0–100)

Adjust parameters in the code for your installation: tank height, sensor offset, calibration, region, and join keys.

secrets.h (template; create and fill with your keys)

// secrets.h - do not commit
#pragma once

// Set your LoRaWAN region in the main sketch (e.g., "EU868", "US915")

// OTAA credentials from The Things Stack (TTS/TTN)
static const char* APP_EUI = "70B3D57EDXXXXXXX"; // also called JoinEUI (hex string, no spaces)
static const char* APP_KEY = "5C8A...F2B";       // 16-byte hex string, 32 hex chars

// Optional: if your network requires DevEUI to be set manually, define it:
static const char* DEV_EUI = ""; // leave empty to use onboard value if supported

lora-water-level-telemetry.ino

/*
  LoRa Water Level Telemetry
  Hardware: Arduino MKR WAN 1310 + JSN-SR04T + INA219
  Features:
    - JSN-SR04T distance measurement with median filtering
    - Tank geometry conversion to level (%) and volume (L)
    - INA219 current/power of the JSN sensor line
    - LoRaWAN OTAA join and uplink payload
    - Low power sleep between measurements
*/

#include <MKRWAN.h>
#include <ArduinoLowPower.h>
#include <Wire.h>
#include <Adafruit_INA219.h>
#include "secrets.h"

// ---------------------- Region and LoRaWAN ----------------------
String REGION = "EU868"; // set to "EU868", "US915", "AS923", etc.
LoRaModem modem;

// LoRa settings
const bool USE_ADR = true;
const bool CONFIRMED = false;  // use unconfirmed to save airtime unless you need ACK
int DR = 3;                    // data rate; depends on region, tune as needed

// ---------------------- Sensor Pins -----------------------------
const int PIN_TRIG = 6;  // D6
const int PIN_ECHO = 7;  // D7 via 10k/20k divider

// ---------------------- Timing ------------------------------
const uint32_t MEAS_INTERVAL_SEC = 300; // 5 minutes
const uint8_t SAMPLES = 7;              // median of 7 for robustness

// ---------------------- Tank Calibration --------------------
const float TANK_HEIGHT_MM = 2000.0f;    // distance from sensor face to tank bottom in mm
const float SENSOR_OFFSET_MM = 45.0f;    // dead zone/holder offset; subtract from measured distance
const float TANK_DIAMETER_MM = 1000.0f;  // cylindrical tank example
// Use a simple cylinder. For complex geometries, replace volume calculation.
float litersFromHeight(float waterHeightMm) {
  // Cylinder volume V = pi * r^2 * h; convert mm^3 to L
  const float r_mm = TANK_DIAMETER_MM / 2.0f;
  double mm3 = 3.14159265358979323846 * r_mm * r_mm * (double)waterHeightMm;
  return (float)(mm3 / 1e6); // 1e6 mm^3 per liter
}

// ---------------------- INA219 -------------------------------
Adafruit_INA219 ina219; // default address 0x40

// ---------------------- Utilities ----------------------------
static uint16_t clampU16(int32_t v) { if (v < 0) return 0; if (v > 65535) return 65535; return (uint16_t)v; }

uint32_t pulseInTimeout(uint8_t pin, uint8_t state, uint32_t timeout_us) {
  // Safe pulseIn with timeout
  return pulseIn(pin, state, timeout_us);
}

float measureDistanceMm() {
  // Trigger the JSN-SR04T and measure echo duration
  digitalWrite(PIN_TRIG, LOW);
  delayMicroseconds(3);
  digitalWrite(PIN_TRIG, HIGH);
  delayMicroseconds(12);
  digitalWrite(PIN_TRIG, LOW);

  // Echo timeout at e.g., 30 ms = ~5 m of range (speed of sound ~343 m/s)
  uint32_t duration = pulseInTimeout(PIN_ECHO, HIGH, 30000UL);
  if (duration == 0) return NAN;

  // Distance in cm: duration_us / 58.2; convert to mm
  float distance_mm = (float)duration / 58.2f * 10.0f;
  return distance_mm;
}

float medianOfSamples(uint8_t n) {
  float buf[15]; // up to 15 samples
  if (n > 15) n = 15;
  uint8_t count = 0;
  for (uint8_t i = 0; i < n; i++) {
    float d = measureDistanceMm();
    if (!isnan(d) && d > 30 && d < 6000) { // plausible gate
      buf[count++] = d;
    }
    delay(60);
  }
  if (count == 0) return NAN;
  // insertion sort
  for (uint8_t i = 1; i < count; i++) {
    float key = buf[i];
    int j = i - 1;
    while (j >= 0 && buf[j] > key) { buf[j+1] = buf[j]; j--; }
    buf[j+1] = key;
  }
  return buf[count / 2];
}

bool readINA219(float &busVolts, float &currentmA) {
  busVolts = ina219.getBusVoltage_V(); // bus voltage (V)
  currentmA = ina219.getCurrent_mA();  // current (mA)
  return true;
}

void sleepSeconds(uint32_t s) {
  // Sleep in 8s chunks due to library constraints
  while (s >= 8) { LowPower.sleep(8000); s -= 8; }
  if (s > 0) { LowPower.sleep(s * 1000); }
}

void setupSerial() {
  Serial.begin(115200);
  while (!Serial && millis() < 4000) { ; }
}

// ---------------------- Setup -------------------------------
void setup() {
  setupSerial();
  pinMode(PIN_TRIG, OUTPUT);
  pinMode(PIN_ECHO, INPUT);
  digitalWrite(PIN_TRIG, LOW);

  Wire.begin();
  if (!ina219.begin()) {
    Serial.println("INA219 not found. Check wiring.");
  } else {
    // Configure INA219 calibration; default is ~0.1 ohm shunt on breakout
    ina219.setCalibration_32V_2A();
  }

  // LoRa modem init
  if (!modem.begin(REGION)) {
    Serial.println("Failed to start LoRa modem. Check region/antenna.");
    while (1) { delay(1000); }
  }
  Serial.print("Modem version: "); Serial.println(modem.version());
  Serial.print("Device EUI: "); Serial.println(modem.deviceEUI());

  // ADR and DR
  modem.setADR(USE_ADR);
  if (!USE_ADR) modem.dataRate(DR);

  // OTAA join
  int connected = 0;
  if (strlen(DEV_EUI) > 0) {
    modem.setDevEUI(DEV_EUI);
  }
  Serial.println("Joining LoRaWAN...");
  connected = modem.joinOTAA(APP_EUI, APP_KEY);
  if (!connected) {
    Serial.println("Join failed. Retrying with a slow backoff...");
    for (int i = 0; i < 5 && !connected; i++) {
      delay(5000 * (i + 1));
      connected = modem.joinOTAA(APP_EUI, APP_KEY);
    }
  }
  if (!connected) {
    Serial.println("Join failed permanently. Check keys/region.");
    // You might still want to continue to allow offline validation.
  } else {
    Serial.println("Joined LoRaWAN.");
  }

  // Set low power mode for modem if supported
  modem.minPollInterval(60); // reduce network overhead
}

// ---------------------- Loop -------------------------------
void loop() {
  // Measure distance with median filtering
  float raw_mm = medianOfSamples(SAMPLES);
  float busV = NAN, curmA = NAN;
  readINA219(busV, curmA);

  float corrected_mm = raw_mm - SENSOR_OFFSET_MM;
  if (isnan(raw_mm) || corrected_mm < 0) corrected_mm = 0;

  // Convert to water height above bottom
  float height_mm = TANK_HEIGHT_MM - corrected_mm;
  if (height_mm < 0) height_mm = 0;
  if (height_mm > TANK_HEIGHT_MM) height_mm = TANK_HEIGHT_MM;

  float liters = litersFromHeight(height_mm);
  uint8_t level_pct = (uint8_t)((height_mm / TANK_HEIGHT_MM) * 100.0f + 0.5f);

  // Build payload
  uint8_t payload[9];
  uint16_t dist_u16 = clampU16((int32_t)(corrected_mm + 0.5f));
  uint16_t mv_u16 = clampU16((int32_t)(busV * 1000.0f + 0.5f));
  uint16_t cur_x10 = clampU16((int32_t)(curmA * 10.0f + 0.5f));
  uint16_t liters_u16 = clampU16((int32_t)(liters + 0.5f));

  payload[0] = (dist_u16 >> 8) & 0xFF;
  payload[1] = (dist_u16) & 0xFF;
  payload[2] = (mv_u16 >> 8) & 0xFF;
  payload[3] = (mv_u16) & 0xFF;
  payload[4] = (cur_x10 >> 8) & 0xFF;
  payload[5] = (cur_x10) & 0xFF;
  payload[6] = (liters_u16 >> 8) & 0xFF;
  payload[7] = (liters_u16) & 0xFF;
  payload[8] = level_pct;

  // Diagnostics to serial
  Serial.print("Raw(mm)="); Serial.print(raw_mm, 1);
  Serial.print(" Corrected(mm)="); Serial.print(corrected_mm, 1);
  Serial.print(" Height(mm)="); Serial.print(height_mm, 1);
  Serial.print(" Level(%)="); Serial.print(level_pct);
  Serial.print(" Volume(L)="); Serial.print(liters, 1);
  Serial.print(" BusV(V)="); Serial.print(busV, 3);
  Serial.print(" I(mA)="); Serial.println(curmA, 2);

  // Transmit
  int err = modem.beginPacket();
  if (err <= 0) {
    Serial.println("beginPacket failed");
  } else {
    modem.write(payload, sizeof(payload));
    err = modem.endPacket(CONFIRMED);
    if (err > 0) {
      Serial.println("Uplink OK");
    } else {
      Serial.print("Uplink failed ("); Serial.print(err); Serial.println(")");
    }
  }

  // Sleep to save power
  sleepSeconds(MEAS_INTERVAL_SEC);
}

Optional TTS/TTN payload formatter (JavaScript) for your application:

// The Things Stack (v3) Uplink Decoder
function decodeUplink(input) {
  const bytes = input.bytes;
  if (bytes.length < 9) {
    return { errors: ["payload too short"] };
  }
  const dist = (bytes[0] << 8) | bytes[1];
  const mv = (bytes[2] << 8) | bytes[3];
  const cur_x10 = (bytes[4] << 8) | bytes[5];
  const liters = (bytes[6] << 8) | bytes[7];
  const level = bytes[8];

  return {
    data: {
      distance_mm: dist,
      bus_mV: mv,
      current_mA: cur_x10 / 10.0,
      volume_l: liters,
      level_percent: level
    }
  };
}

Build/Flash/Run Commands

Use Arduino CLI with the correct FQBN for MKR WAN 1310: arduino:samd:mkrwan1310

On first use, install the core and libraries.

arduino-cli version

# 2) Configure Arduino CLI (create config if needed)
arduino-cli config init

# 3) Update index and install SAMD core for MKR WAN 1310
arduino-cli core update-index
arduino-cli core install arduino:samd@1.8.13

# 4) Install required libraries (pin versions for reproducibility)
arduino-cli lib install "MKRWAN@1.1.0"
arduino-cli lib install "ArduinoLowPower@1.2.2"
arduino-cli lib install "Adafruit INA219@1.2.1"

# 5) Create project folder structure
mkdir -p ~/projects/lora-water-level-telemetry
cd ~/projects/lora-water-level-telemetry

# 6) Place the two files:
#    - lora-water-level-telemetry.ino
#    - secrets.h
#    in the current directory.

# 7) Detect board and port
arduino-cli board list

# Example output:
# Port         Type              FQBN                       Core
# /dev/ttyACM0 Serial Port (USB) arduino:samd:mkrwan1310    arduino:samd
# On Windows this might be COM7, e.g., COM7

# 8) Compile
arduino-cli compile --fqbn arduino:samd:mkrwan1310 .

# 9) Upload (replace PORT accordingly)
arduino-cli upload -p /dev/ttyACM0 --fqbn arduino:samd:mkrwan1310 .

# 10) Open serial monitor at 115200 baud to watch logs
arduino-cli monitor -p /dev/ttyACM0 -c baudrate=115200

If you get permission errors on Linux for /dev/ttyACM0, add your user to the dialout group and re-login:
– sudo usermod -a -G dialout $USER


Step-by-step Validation

Follow these steps to verify each subsystem and the end-to-end telemetry.

1) Local serial diagnostics

  • Power the board via USB with the antenna attached.
  • Open the serial monitor:
  • arduino-cli monitor -p /dev/ttyACM0 -c baudrate=115200
  • On boot, you should see:
  • Modem version and Device EUI printed
  • “Joining LoRaWAN…” then “Joined LoRaWAN.” (if network reachable and keys are correct)
  • A measurement line every MEAS_INTERVAL_SEC seconds:
    • Raw(mm), Corrected(mm), Height(mm), Level(%), Volume(L), BusV(V), I(mA)
  • Move a flat object above the JSN-SR04T at known distances (e.g., 30 cm, 50 cm) and confirm that:
  • Raw and Corrected distances match expectations within ±1–2 cm
  • Level% changes accordingly if your TANK_HEIGHT_MM is configured

Tip: For bench testing without a tank, set TANK_HEIGHT_MM to a smaller value (e.g., 600 mm) to make level% changes more obvious.

2) JSN-SR04T sanity checks

  • If Raw(mm) reads NAN or 0 frequently:
  • Ensure the Echo line is level-shifted with the 10k/20k divider
  • Verify 5V is stable at the sensor VCC pin
  • Increase the pulseIn timeout slightly in measureDistanceMm() if your tank is deep
  • Confirm the sensor face is clean and not tilted with respect to the water surface.

3) INA219 readings

  • Check BusV ~ 5.0 V (may be 4.7–5.2 V depending on USB source).
  • With the JSN-SR04T idle, current may be a few mA; during burst, it spikes higher.
  • If current is always 0:
  • Confirm INA219 address (0x40 default) and wiring (VIN+, VIN-, and VCC=3.3V)
  • Confirm ina219.begin() succeeded (noted on serial)

4) LoRaWAN join and uplink

  • In The Things Stack console:
  • Ensure the device is registered under your application with OTAA.
  • Frequency plan must match REGION in the sketch.
  • After reset, the device should issue a join request, then an uplink.
  • Install the provided uplink decoder in the application’s “Payload formatters” (Uplink) and click Save.
  • In the “Live data” view:
  • After the first measurement, confirm an uplink packet arrives every 5 minutes.
  • Verify decoded fields:
    • distance_mm increases when the water surface moves away from the sensor
    • level_percent reflects tank level
    • bus_mV ≈ ~5000 mV
    • current_mA shows spikes consistent with ultrasonic bursts

5) Tank calibration

  • Measure the actual distance from sensor face to the tank bottom and set TANK_HEIGHT_MM.
  • If the sensor is recessed in a mount or has a dead zone, measure and set SENSOR_OFFSET_MM.
  • Fill the tank to a known fraction (e.g., 50%) and compare level_percent. If off by a constant scale:
  • Check TANK_DIAMETER_MM (if your tank is cylindrical).
  • For rectangular tanks, replace litersFromHeight() with widthlengthheight conversion.
  • Record multiple fill points to verify linearity.

6) End-to-end sanity

  • Confirm consistent uplinks for at least 30–60 minutes.
  • Confirm ADR status on the network (if enabled) and that data rate remains appropriate for link quality.
  • Ensure no MAC command errors or frame counter mismatches occur in the console.

Troubleshooting

  • Join fails or never uplinks:
  • Check antenna is connected and placed away from metal.
  • Verify REGION matches your frequency plan (e.g., EU868 vs US915). Change REGION string in setup.
  • Ensure APP_EUI (JoinEUI) and APP_KEY are correct hex strings with no spaces.
  • Some networks require setting DevEUI explicitly; fill DEV_EUI if needed (check TTS device page).
  • Verify gateway coverage and downlink availability for OTAA. If in a shielded room, move closer to a window.

  • Uplinks arrive but no decoded fields:

  • Ensure the payload decoder is saved and has no syntax errors.
  • Confirm payload size is 9 bytes.

  • Distance readings inconsistent or stuck:

  • JSN-SR04T needs a clean acoustic path; condensation or turbulent surface can cause jitter.
  • Increase SAMPLES or add a larger median window.
  • Reduce environmental acoustic noise and avoid mounting close to tank walls.
  • Ensure trigger pulse width is adequate (10–12 µs is typical) and that TRIG pin is defined as OUTPUT.

  • Echo line damages or erratic input:

  • Never connect 5V Echo directly to MKR pin. Use the exact 10k (series, top) and 20k (to GND, bottom) divider.
  • Check with a multimeter: in HIGH, the divider node should read close to 3.3V.

  • INA219 zero or unrealistic values:

  • Confirm the shunt is actually in series with the JSN-SR04T VCC line (VIN+ to 5V source, VIN- to sensor VCC).
  • Power INA219 at 3.3V so logic levels are coherent with MKR’s I2C.
  • If using a different breakout, note its shunt value and adjust calibration (e.g., setCalibration_32V_1A).

  • Power budget and resets:

  • When powered by USB only, 5V may sag with poor cables. Try a better USB cable or powered hub.
  • If running on LiPo, ensure the battery is charged and check charge status LEDs on MKR WAN 1310.

Improvements

  • Downlink configuration:
  • Add a small downlink parser to allow changing MEAS_INTERVAL_SEC or DR on the fly (e.g., via port 2).
  • Implement a command to trigger an immediate measurement.

  • Advanced filtering and reliability:

  • Implement outlier rejection using interquartile range and adaptive timeouts.
  • Add temperature compensation for speed of sound. If you have a temperature sensor, adjust c = 331 + 0.6*T(m/s).

  • Power optimization:

  • Power-gate the JSN-SR04T via a P-MOSFET controlled by an MKR pin to remove idle draw between measurements.
  • Increase sleep duration and switch to confirmed uplinks only for alerts.

  • Payload optimization:

  • Use a packed bitfield to shrink the payload further, or adopt CayenneLPP if you prefer tooling compatibility.
  • Add battery voltage of the MKR board if you bring it into measurement via an analog divider (3.3V-limited).

  • Geometry generalization:

  • Replace the cylinder model with piecewise linear or lookup-table calibration for irregular tanks.

  • Robustness:

  • Add a watchdog timer reset if join/uplink fails N times.
  • CRC32 of the data pre-transmission for integrity (not needed for LoRaWAN but useful for internal checks).

  • Cloud integration:

  • Push decoded data to a time-series database (InfluxDB) and visualize with Grafana via TTS MQTT.

Final Checklist

  • Hardware
  • Antenna firmly connected to MKR WAN 1310.
  • JSN-SR04T VCC=5V, GND common, TRIG=D6, ECHO to D7 through 10k/20k divider.
  • INA219 wired: VIN+ to 5V source, VIN- to sensor VCC; SDA/SCL to MKR; VCC=3.3V; GND common.
  • Enclosure protects from moisture; sensor face unobstructed.

  • Software

  • Arduino CLI installed and working.
  • Core arduino:samd@1.8.13 installed.
  • Libraries installed: MKRWAN 1.1.0, ArduinoLowPower 1.2.2, Adafruit INA219 1.2.1.
  • secrets.h contains correct APP_EUI/APP_KEY (and DEV_EUI if required).
  • REGION matches your frequency plan (e.g., EU868 or US915).
  • FQBN arduino:samd:mkrwan1310 used for compile/upload.

  • Validation

  • Serial logs show successful join (or reason for failure) and periodic measurements.
  • JSN-SR04T distance values vary appropriately with target range.
  • INA219 reports plausible bus voltage (~5000 mV) and current.
  • TTS/TTN receives uplinks with 9-byte payload and decodes fields correctly.
  • Level% and liters track real tank conditions after calibration.

  • Deployment

  • Sleep interval set to meet duty cycle and battery goals.
  • ADR enabled if stationary and within a stable network coverage area.
  • Alarm thresholds considered and possibly implemented via downlink or local logic.

With these steps complete, you have a dependable LoRaWAN water level telemetry node built on Arduino MKR WAN 1310 with ultrasonic sensing and power diagnostics, ready for field deployment.

Find this product and/or books on this topic on Amazon

Go to Amazon

As an Amazon Associate, I earn from qualifying purchases. If you buy through this link, you help keep this project running.

Quick Quiz

Question 1: What type of sensor is used in the project?




Question 2: Which Arduino model is utilized for the telemetry node?




Question 3: What is the purpose of the INA219 in the project?




Question 4: Which command-line interface is used to compile and flash the sketch?




Question 5: What type of network access is required for the project?




Question 6: What is the main objective of the project?




Question 7: What operating systems are supported for this project?




Question 8: What is the significance of OTAA in LoRaWAN?




Question 9: Which component is NOT required for this project?




Question 10: What is the function of the filtering and calibration mentioned in the project?




Carlos Núñez Zorrilla
Carlos Núñez Zorrilla
Electronics & Computer Engineer

Telecommunications Electronics Engineer and Computer Engineer (official degrees in Spain).

Follow me:
Scroll to Top