Practical case: Arduino MKR GSM 1400 GNSS/GSM Tracker

Practical case: Arduino MKR GSM 1400 GNSS/GSM Tracker — hero

Objective and use case

What you’ll build: Build a robust, field-ready GNSS-GSM asset tracker using the Arduino MKR GSM 1400, NEO-M8N, and BNO055. The device will periodically read GNSS position and orientation/acceleration, then post JSON telemetry over GSM to a server endpoint.

Why it matters / Use cases

  • Real-time tracking of assets in remote locations using GNSS data for precise location.
  • Monitoring environmental conditions and movement of vehicles or equipment in logistics.
  • Implementing safety measures by tracking the location of valuable assets in transit.
  • Collecting data for fleet management systems to optimize routes and reduce costs.

Expected outcome

  • Telemetry data sent every 10 seconds with a location accuracy of within 5 meters.
  • GSM connectivity with a minimum uptime of 95% in urban areas.
  • Latency of less than 2 seconds for data transmission to the server.
  • Ability to handle at least 100 packets of telemetry data per hour.

Audience: Developers and engineers interested in IoT applications; Level: Intermediate.

Architecture/flow: The system architecture includes the Arduino MKR GSM 1400 interfacing with the NEO-M8N for GNSS data and the BNO055 for orientation, sending data over GSM to a cloud server.

Advanced Hands‑On: GNSS + GSM Asset Tracker on Arduino MKR GSM 1400 + NEO‑M8N + BNO055

Objective: Build a robust, field‑ready gnss-gsm-asset-tracker using the exact device model Arduino MKR GSM 1400 + NEO-M8N + BNO055. The device periodically reads GNSS position and orientation/acceleration, then posts JSON telemetry over GSM (GPRS/EDGE/3G) to a server endpoint. We’ll use PlatformIO for a reproducible, version‑pinned build and command‑line workflow.

Note: Because we selected a board different from Arduino UNO (we’re using MKR GSM 1400), we will use PlatformIO (not Arduino CLI), and include driver notes and PlatformIO commands accordingly.


Prerequisites

  • OS: Windows 10/11, macOS 12+, or Linux (Ubuntu 20.04+). USB 2.0/3.0 port.
  • Python 3.8+ with pip.
  • PlatformIO Core (CLI) installed via pip.
  • A working micro SIM card with an active data plan; know the APN, APN username, APN password (many providers use blank username/password).
  • A reachable HTTP endpoint for testing. Easiest: generate a unique receiver at https://webhook.site/ (copy the unique path/UUID).
  • Stable internet on the development computer (to fetch libs and platforms).
  • Basic ESD safety: handle boards/modules on a non‑conductive surface.

Driver notes:
– Arduino MKR GSM 1400 uses native USB CDC (no CP210x/CH34x needed). On Windows 10/11, it should enumerate automatically. If not recognized, install “Arduino SAMD Boards” USB driver via Arduino IDE or Zadig. On macOS/Linux, it appears as /dev/cu.usbmodemNNN or /dev/ttyACM0.
– If the port seems to “disappear”, double‑tap the MKR GSM 1400 reset button to force the bootloader COM port for upload.


Materials (exact models)

  • 1 × Arduino MKR GSM 1400 board (SAMD21 + u‑blox SARA‑U201 modem).
  • 1 × GNSS module: u‑blox NEO‑M8N breakout with I2C exposed (address 0x42) and 3.3 V compatibility.
  • 1 × 9‑DoF absolute orientation IMU: Bosch BNO055 breakout (default I2C address 0x28, 3.3 V compatible).
  • 1 × External GSM antenna (u.FL) for MKR GSM 1400.
  • 1 × External GNSS antenna (u.FL or SMA with pigtail, depending on the NEO‑M8N breakout).
  • 1 × Micro SIM card (data plan).
  • Jumper wires (dupont), preferably color‑coded.
  • 1 × Micro USB cable (data‑capable).
  • Optional: 4.7 kΩ pull‑up resistors for SDA/SCL if your breakout does not include them (many do).

Power safety:
– MKR GSM 1400 runs at 3.3 V logic. Ensure both NEO‑M8N and BNO055 breakouts are 3.3 V compatible or include level shifting. Power them from the 3.3 V pin, not 5 V.


Setup/Connection

SIM and Antennas

  1. Power off the board.
  2. Insert the micro SIM (contacts facing down) into the MKR GSM 1400 slot.
  3. Connect the GSM antenna to the u.FL connector on MKR GSM 1400.
  4. Connect the GNSS antenna to NEO‑M8N’s antenna connector (u.FL or adapter as needed).
  5. Ensure both antenna pigtails are fully seated; intermittent antennas are a common cause of “no service” or “no fix”.

Power and I2C Wiring

We will use I2C for both sensors to keep UART free and simplify wiring.

  • Voltage rails:
  • Use only 3.3 V from the MKR GSM 1400 to power the sensors.
  • Common ground between all modules.

  • I2C:

  • MKR GSM 1400 I2C pins: labeled SDA and SCL on the header near 3.3 V/GND (dedicated SDA/SCL pins).
  • NEO‑M8N DDC/I2C: SDA to SDA, SCL to SCL (address 0x42).
  • BNO055: SDA to SDA, SCL to SCL (default address 0x28 with ADR pin low).
  • If your sensor breakouts do not have onboard pull‑ups on SDA and SCL, add 4.7 kΩ from SDA to 3.3 V and from SCL to 3.3 V. Do not pull up to 5 V.

Connection Table

MKR GSM 1400 Pin NEO‑M8N Pin (I2C mode) BNO055 Pin Notes
3.3V VCC (3.3V) VIN (3.3V) Power both sensors from 3.3 V only
GND GND GND Common ground
SDA SDA/DDC_SDA SDA I2C data line
SCL SCL/DDC_SCL SCL I2C clock line
1PPS (optional) Optional timing pin (not used)
TX/RX (unused) We’re not using UART for GNSS in this build

Important: Do not connect any 5 V signals to MKR pins. Ensure the GNSS and IMU breakouts are I2C‑enabled and 3.3 V compatible.


Full Code

We’ll use PlatformIO with pinned library versions for reproducibility. The project structure:

  • platformio.ini
  • src/main.cpp

Replace placeholders for APN, APN_USER, APN_PASS, and WEBHOOK_PATH in the code as instructed.

platformio.ini

[env:mkrgsm1400]
platform = atmelsam
board = mkrgsm1400
framework = arduino
upload_port = auto
monitor_port = auto
monitor_speed = 115200
build_flags =
  -D PIO_FRAMEWORK_ARDUINO_ENABLE_CDC
  -D USBCON
lib_deps =
  arduino-libraries/MKRGSM@^1.5.0
  arduino-libraries/ArduinoHttpClient@^0.6.0
  sparkfun/SparkFun u-blox GNSS v3@^3.1.12
  adafruit/Adafruit BNO055@^1.6.3
  adafruit/Adafruit Unified Sensor@^1.1.14
  bblanchon/ArduinoJson@^6.21.3

src/main.cpp

#include <Arduino.h>
#include <Wire.h>
#include <MKRGSM.h>
#include <ArduinoHttpClient.h>
#include <ArduinoJson.h>

// GNSS
#include <SparkFun_u-blox_GNSS_v3.h> // SFE_UBLOX_GNSS

// IMU
#include <Adafruit_Sensor.h>
#include <Adafruit_BNO055.h>
#include <utility/imumaths.h>

// ====== User configuration (edit these) ======
static const char APN[]      = "internet";   // Replace with your carrier APN
static const char APN_USER[] = "";           // Often empty
static const char APN_PASS[] = "";           // Often empty
static const char SIM_PIN[]  = "";           // SIM PIN if required; else empty

// HTTP endpoint (non-SSL for simplicity). For SSL, see Improvements section.
static const char HOST[]     = "webhook.site";      // Or your server
static const int  PORT       = 80;                  // 80 for HTTP
static const char WEBHOOK_PATH[] = "/YOUR-UNIQUE-PATH"; // e.g., /a1b2c3d4-... from webhook.site
// ============================================

GSM gsmAccess;
GPRS gprs;
GSMClient netClient;
HttpClient httpClient(netClient, HOST, PORT);
GSMModem modem;

SFE_UBLOX_GNSS gnss;        // I2C GNSS at 0x42
Adafruit_BNO055 bno(55, 0x28); // 0x28 default; use 0x29 if ADR high

// Timing
const unsigned long POST_INTERVAL_MS = 30000; // 30s
unsigned long lastPost = 0;

// Simple I2C scan for validation
void i2cScan() {
  Serial.println(F("[I2C] Scanning..."));
  byte count = 0;
  for (byte address = 1; address < 127; address++) {
    Wire.beginTransmission(address);
    byte error = Wire.endTransmission();
    if (error == 0) {
      Serial.print(F(" - Found 0x"));
      if (address < 16) Serial.print('0');
      Serial.println(address, HEX);
      count++;
    }
  }
  Serial.print(F("[I2C] Devices found: "));
  Serial.println(count);
}

// Attempt GSM + GPRS connection with timeout
bool connectCellular(unsigned long timeoutMs = 120000) {
  Serial.println(F("[GSM] Starting modem..."));
  unsigned long start = millis();

  // Initialize GSM access (SIM PIN if any)
  while (gsmAccess.begin(SIM_PIN) != GSM_READY) {
    if (millis() - start > timeoutMs) {
      Serial.println(F("[GSM] ERROR: Modem init timeout"));
      return false;
    }
    Serial.println(F("[GSM] Retrying modem init..."));
    delay(2000);
  }
  Serial.println(F("[GSM] Modem ready"));

  // Retrieve IMEI for device ID
  String imei = modem.getIMEI();
  if (imei.length() > 0) {
    Serial.print(F("[GSM] Modem IMEI: "));
    Serial.println(imei);
  } else {
    Serial.println(F("[GSM] WARNING: Could not read IMEI"));
  }

  Serial.print(F("[GPRS] Attaching to APN: "));
  Serial.println(APN);
  start = millis();
  while (gprs.attachGPRS(APN, APN_USER, APN_PASS) != GPRS_READY) {
    if (millis() - start > timeoutMs) {
      Serial.println(F("[GPRS] ERROR: APN attach timeout"));
      return false;
    }
    Serial.println(F("[GPRS] Retrying GPRS attach..."));
    delay(2000);
  }
  Serial.println(F("[GPRS] GPRS attached."));

  // Optional: show local IP (if supported)
  IPAddress ip = gprs.getIPAddress();
  Serial.print(F("[GPRS] Local IP: "));
  Serial.println(ip);

  return true;
}

bool initGNSS() {
  Serial.println(F("[GNSS] Initializing u-blox over I2C (0x42)..."));
  if (!gnss.begin()) {
    Serial.println(F("[GNSS] ERROR: GNSS not detected. Check wiring and power."));
    return false;
  }

  // Disable NMEA on I2C, use UBX only for efficiency
  gnss.setI2COutput(COM_TYPE_UBX);
  gnss.setNavigationFrequency(1); // 1 Hz update
  // Save config to BBR/Flash if supported
  gnss.saveConfiguration();

  Serial.println(F("[GNSS] OK"));
  return true;
}

bool initBNO() {
  Serial.println(F("[BNO055] Initializing..."));
  if (!bno.begin(OPERATION_MODE_NDOF)) {
    Serial.println(F("[BNO055] ERROR: Could not find BNO055. Check wiring/address."));
    return false;
  }
  delay(20);
  bno.setExtCrystalUse(true); // If breakout has a crystal; harmless if not
  Serial.println(F("[BNO055] OK"));
  return true;
}

// Read GNSS snapshot; returns true if valid fix
bool readGNSS(double &lat, double &lon, double &alt_m, float &speed_kmh, uint8_t &sats, uint8_t &fixType) {
  // Poll latest NAV-PVT
  if (!gnss.getPVT()) {
    return false; // no new data
  }

  fixType = gnss.getFixType(); // 0=no fix, 2=2D, 3=3D, etc.
  sats    = gnss.getSIV();

  long lat_1e7 = gnss.getLatitude();
  long lon_1e7 = gnss.getLongitude();
  long alt_mm  = gnss.getAltitude();    // mm above ellipsoid
  long gnd_mmps = gnss.getGroundSpeed();// mm/s

  lat = lat_1e7 / 1e7;
  lon = lon_1e7 / 1e7;
  alt_m = alt_mm / 1000.0;
  speed_kmh = (gnd_mmps / 1000.0f) * 3.6f;

  return (fixType >= 2); // consider 2D/3D as valid
}

void readIMU(float &heading_deg, float &pitch_deg, float &roll_deg, float &accel_ms2) {
  sensors_event_t orientationData, angularVelocityData, linearAccelData, magnetometerData, accelData, gyroData, tempData;
  bno.getEvent(&orientationData, Adafruit_BNO055::VECTOR_EULER);
  bno.getEvent(&accelData, Adafruit_BNO055::VECTOR_ACCELEROMETER);

  heading_deg = orientationData.orientation.x;
  roll_deg    = orientationData.orientation.y;
  pitch_deg   = orientationData.orientation.z;

  // Magnitude of acceleration vector (m/s^2)
  accel_ms2 = sqrt(accelData.acceleration.x * accelData.acceleration.x +
                   accelData.acceleration.y * accelData.acceleration.y +
                   accelData.acceleration.z * accelData.acceleration.z);
}

bool postTelemetry(const String &payload) {
  Serial.println(F("[HTTP] POST begin"));
  int err = httpClient.post(WEBHOOK_PATH, "application/json", payload);
  if (err != 0) {
    Serial.print(F("[HTTP] ERROR posting: "));
    Serial.println(err);
    return false;
  }

  int statusCode = httpClient.responseStatusCode();
  String response = httpClient.responseBody();

  Serial.print(F("[HTTP] Status: "));
  Serial.println(statusCode);
  Serial.print(F("[HTTP] Body: "));
  Serial.println(response);

  return (statusCode >= 200 && statusCode < 300);
}

String buildJSON(const String &deviceId,
                 double lat, double lon, double alt_m, float speed_kmh,
                 uint8_t sats, uint8_t fixType,
                 float heading_deg, float pitch_deg, float roll_deg, float accel_ms2) {
  StaticJsonDocument<512> doc;
  doc["device"] = deviceId;
  doc["ts"] = millis();

  JsonObject gnssObj = doc.createNestedObject("gnss");
  gnssObj["lat"] = lat;
  gnssObj["lon"] = lon;
  gnssObj["alt_m"] = alt_m;
  gnssObj["speed_kmh"] = speed_kmh;
  gnssObj["sats"] = sats;
  gnssObj["fixType"] = fixType;

  JsonObject imuObj = doc.createNestedObject("imu");
  imuObj["heading_deg"] = heading_deg;
  imuObj["pitch_deg"] = pitch_deg;
  imuObj["roll_deg"] = roll_deg;
  imuObj["accel_ms2"] = accel_ms2;

  String out;
  serializeJson(doc, out);
  return out;
}

String cachedIMEI;

void setup() {
  pinMode(LED_BUILTIN, OUTPUT);
  digitalWrite(LED_BUILTIN, LOW);

  Serial.begin(115200);
  while (!Serial && millis() < 3000) { } // Wait up to 3s for USB

  Serial.println(F("\n=== GNSS-GSM Asset Tracker: MKR GSM 1400 + NEO-M8N + BNO055 ==="));

  Wire.begin();
  Wire.setClock(400000); // 400 kHz if supported
  i2cScan();

  if (!initGNSS()) {
    Serial.println(F("[BOOT] GNSS init failed; continuing to retry later."));
  }
  if (!initBNO()) {
    Serial.println(F("[BOOT] BNO055 init failed; check wiring."));
  }

  if (connectCellular()) {
    cachedIMEI = modem.getIMEI();
    if (cachedIMEI.length() == 0) cachedIMEI = "unknown";
  } else {
    Serial.println(F("[BOOT] Cellular attach failed, will retry in loop."));
  }

  lastPost = 0;
  digitalWrite(LED_BUILTIN, HIGH); // indicate boot complete
}

void loop() {
  // Periodic posting
  if (millis() - lastPost >= POST_INTERVAL_MS) {
    lastPost = millis();

    // Ensure cellular is connected
    if (gprs.status() != GPRS_READY) {
      Serial.println(F("[GPRS] Reattaching..."));
      if (!connectCellular()) {
        Serial.println(F("[GPRS] ERROR: Cannot attach. Skipping this cycle."));
        return;
      }
    }

    // GNSS read
    double lat = NAN, lon = NAN, alt_m = NAN;
    float speed_kmh = NAN;
    uint8_t sats = 0, fixType = 0;
    bool hasFix = readGNSS(lat, lon, alt_m, speed_kmh, sats, fixType);

    if (!hasFix) {
      Serial.println(F("[GNSS] No valid fix yet. Ensure antenna has sky view."));
    } else {
      Serial.print(F("[GNSS] FixType=")); Serial.print(fixType);
      Serial.print(F(" Sats=")); Serial.print(sats);
      Serial.print(F(" Lat=")); Serial.print(lat, 7);
      Serial.print(F(" Lon=")); Serial.print(lon, 7);
      Serial.print(F(" Alt(m)=")); Serial.print(alt_m, 2);
      Serial.print(F(" Speed(km/h)=")); Serial.println(speed_kmh, 2);
    }

    // IMU read
    float heading_deg = NAN, pitch_deg = NAN, roll_deg = NAN, accel_ms2 = NAN;
    readIMU(heading_deg, pitch_deg, roll_deg, accel_ms2);
    Serial.print(F("[IMU] Heading/Pitch/Roll="));
    Serial.print(heading_deg, 1); Serial.print('/');
    Serial.print(pitch_deg, 1);  Serial.print('/');
    Serial.println(roll_deg, 1);

    // Build JSON and POST (even without fix, send telemetry so backend can observe device state)
    String payload = buildJSON(cachedIMEI.length() ? cachedIMEI : "unknown",
                               lat, lon, alt_m, speed_kmh, sats, fixType,
                               heading_deg, pitch_deg, roll_deg, accel_ms2);

    Serial.print(F("[JSON] ")); Serial.println(payload);
    bool ok = postTelemetry(payload);
    if (!ok) {
      Serial.println(F("[HTTP] POST failed."));
      digitalWrite(LED_BUILTIN, LOW);
    } else {
      Serial.println(F("[HTTP] POST success."));
      digitalWrite(LED_BUILTIN, HIGH);
    }
  }

  delay(50);
}

Notes:
– This example uses HTTP (port 80) to minimize TLS/certificate friction. You can upgrade to TLS with GSMSSLClient and CA injection; see Improvements.
– For BNO055, orientation output depends on calibration. Allow a minute of device motion for auto‑calibration, or see Adafruit docs for persistent calibration.


Build/Flash/Run Commands

Install PlatformIO Core and build/upload from the terminal. Replace with your actual serial port if needed.

python3 -m pip install --upgrade pip
python3 -m pip install --upgrade platformio

# 2) Verify environment
pio system info

# 3) Create project folder and place files
#   Ensure platformio.ini and src/main.cpp are in your project directory.

# 4) Fetch platforms and libraries (per platformio.ini)
pio pkg update

# 5) Clean, build, and upload (auto-detect port)
pio run -t clean -e mkrgsm1400
pio run -e mkrgsm1400
pio run -t upload -e mkrgsm1400

# If upload fails to find the port, specify it (examples):
#   - Windows: COM5
#   - Linux:   /dev/ttyACM0
#   - macOS:   /dev/cu.usbmodem14101
pio run -t upload -e mkrgsm1400 --upload-port COM5

# 6) Open serial monitor at 115200 baud
pio device monitor -b 115200

Windows driver tip: If the COM port disconnects during upload, double‑tap the reset button on MKR GSM 1400 to re‑enumerate the bootloader port, then rerun the upload command with that port.


Step‑by‑Step Validation

  1. I2C device detection
  2. Connect the board via USB, open the serial monitor: pio device monitor -b 115200.
  3. On boot, you should see:

    • “[I2C] Scanning…” followed by:
    • “Found 0x28” (BNO055) and “Found 0x42” (NEO‑M8N).
    • If not detected:
    • Verify SDA/SCL wiring and 3.3 V power.
    • Ensure breakout pull‑ups or enable your own (4.7 kΩ).
    • Reboot and scan again.
  4. GNSS initialization

  5. Confirm “[GNSS] OK”. If it fails, it prints an error.
  6. Move the GNSS antenna to a window or outdoors. Cold start to 3D fix could take 30–60 seconds or longer without A‑GNSS.

  7. IMU initialization

  8. Confirm “[BNO055] OK”.
  9. Observe “[IMU] Heading/Pitch/Roll=…”
  10. Move/rotate the device and confirm heading/pitch/roll change.

  11. Cellular attach (GSM/GPRS)

  12. Observe “[GSM] Modem ready” and “[GPRS] GPRS attached.”
  13. If APN is wrong or coverage is poor, you’ll see attach retries and eventually a timeout.
  14. The local IP should print, e.g., “[GPRS] Local IP: 10.x.x.x”.

  15. GNSS fix and telemetry content

  16. Once satellites are visible:
    • “[GNSS] FixType=2/3 Sats=… Lat=… Lon=… Alt(m)=… Speed(km/h)=…”
    • FixType=3 is 3D fix (preferred).
  17. A JSON payload prints under “[JSON] …” each 30 seconds:

    • It includes device (IMEI), ts (millis), gnss lat/lon/alt/speed/sats/fixType, imu heading/pitch/roll/accel.
  18. HTTP POST to server

  19. The code posts to HOST:webhook.site with your unique WEBHOOK_PATH.
  20. Expected:
    • “[HTTP] Status: 200”
    • “[HTTP] POST success.”
  21. On https://webhook.site/ (your token page), you should see incoming requests with JSON payloads. Validate fields visually or inspect the raw body.

  22. Power/performance sanity

  23. LED on when last POST succeeded; off if last POST failed.
  24. Typical current draw increases during GSM transmission bursts. If you transition to battery power later, ensure sufficient supply (peaks can exceed 500 mA).

Troubleshooting

  • Board not detected over USB
  • Use a known good data cable.
  • Double‑tap reset for bootloader mode; reupload with the new port.
  • Windows: Install Arduino SAMD driver if needed. Check Device Manager under “Ports (COM & LPT)”.

  • I2C devices not found

  • Confirm 3.3 V power and GND.
  • Confirm SDA/SCL orientation; do not swap them.
  • Check that breakout boards expose I2C (some NEO‑M8N boards require solder jumpers to enable DDC/I2C).
  • If both devices are missing, suspect SDA/SCL pull‑ups or physical bus fault.

  • GNSS no fix

  • Ensure the GNSS antenna has clear sky view; avoid indoors.
  • Use a high‑gain active antenna if possible; verify the breakout supplies antenna bias if needed.
  • Wait several minutes for a cold start; first fix can be slow without assistance.
  • Confirm you see “[GNSS] FixType” increasing from 0 to 2/3; check number of satellites.

  • GSM cannot attach (GPRS)

  • Confirm antenna is attached to MKR GSM 1400.
  • Verify SIM is active and has data balance.
  • Double‑check APN, username, and password. Some carriers require case‑sensitive APN names.
  • Try with SIM PIN empty or set SIM_PIN accordingly.
  • Move to an area with 2G/3G coverage; some regions have sunset 2G/3G networks.
  • If the SIM is locked, use a phone to disable PIN temporarily and retry.

  • HTTP timeouts or errors

  • If “[HTTP] ERROR posting”, ensure the host/path are correct and network is up.
  • Some networks block port 80; try a different host or test plain TCP connectivity by posting less frequently.
  • If you must use HTTPS, see Improvements for TLS configuration details.

  • BNO055 erratic orientation

  • Allow time for calibration. Move through multiple axes.
  • Use bno.getCalibration() to examine sys/gyro/accel/mag calibration levels.
  • Ensure stable power; noisy VIN can disturb readings.

  • Memory or stability issues

  • Reduce JSON payload size.
  • Lower GNSS rate to 1 Hz (already configured).
  • Avoid creating large Strings repeatedly; consider a StaticJsonDocument with capped capacity (we’re using 512 bytes).

Improvements

  • HTTPS/TLS
  • Switch to GSMSSLClient for encrypted transport:
    • Replace GSMClient netClient; with GSMSSLClient netClient;.
    • Use port 443 and a host supporting modern ciphers for SARA‑U201.
    • Load the server certificate/CA into the modem if validation is required; consult MKRGSM examples (NB: certificate memory is limited and may require PEM to DER conversion and modem storage).
  • Alternatively, terminate TLS on a nearby gateway and keep device HTTP if acceptable for your threat model.

  • MQTT telemetry

  • Use Eclipse Paho MQTT library or arduino-mqtt with GSMClient/GSMSSLClient to publish to an MQTT broker.
  • Topics could include: asset/<imei>/telemetry.

  • Assisted‑GNSS (A‑GNSS)

  • Use u‑blox AssistNow Online/Offline to speed up TTFF.
  • The SparkFun u‑blox GNSS library supports aiding data injection over I2C; fetch assistance over GSM and push to the GNSS module.

  • Power management

  • Increase POST_INTERVAL_MS to reduce data and power usage.
  • Use modem power‑saving modes (PSM/eDRX if available).
  • Sleep SAMD21 between cycles (standby mode) and wake via RTC.

  • Geofencing and event‑driven uploads

  • Post only on movement or exit/entry of geofences to save data.
  • Use BNO055 acceleration thresholds to detect motion start/stop.

  • Local buffering

  • Cache telemetry to flash/EEPROM or external FRAM when GPRS is down; resubmit later.

  • Integrity and signing

  • Add HMAC signature of payload using a pre‑shared key.
  • Use nonce/timestamp validation on server to resist replay.

  • Diagnostics

  • Log RSSI/CSQ, registration status, and GNSS DOP/accuracy fields for server‑side quality grading.
  • Report battery voltage if you add a LiPo and measure via analog input.

  • UBX tuning

  • Configure dynamic model (e.g., portable/automotive) using UBX‑CFG‑NAV5 for better performance depending on use case.
  • Disable unnecessary NMEA streams to conserve bandwidth and parsing time (already using UBX only over I2C).

Final Checklist

  • Hardware
  • [ ] Exact device model used: Arduino MKR GSM 1400 + NEO‑M8N + BNO055.
  • [ ] GSM antenna connected to MKR GSM 1400.
  • [ ] GNSS antenna connected to NEO‑M8N.
  • [ ] NEO‑M8N and BNO055 powered from 3.3 V; common ground to MKR.
  • [ ] I2C wiring: SDA→SDA, SCL→SCL; pull‑ups present (on breakout or external).

  • Software

  • [ ] PlatformIO installed and pio system info works.
  • [ ] platformio.ini and src/main.cpp placed correctly.
  • [ ] Libraries resolved with pio pkg update.
  • [ ] APN and WEBHOOK_PATH set to your values.
  • [ ] Build succeeds: pio run -e mkrgsm1400.

  • Flash and Monitor

  • [ ] Upload succeeds: pio run -t upload -e mkrgsm1400.
  • [ ] Serial monitor at 115200 shows I2C scan with 0x28 and 0x42.
  • [ ] “[GNSS] OK” and “[BNO055] OK” messages on boot.
  • [ ] “[GSM] Modem ready” and “[GPRS] GPRS attached.” and IP printed.

  • Validation

  • [ ] GNSS fixType 2/3 with valid lat/lon.
  • [ ] IMU heading/pitch/roll change with device orientation.
  • [ ] JSON payload printed locally.
  • [ ] HTTP status 200 on POST.
  • [ ] Data visible at your webhook.site endpoint.

With this build, you have a fully working gnss-gsm-asset-tracker that combines positional data and orientation/acceleration, reports over cellular networks, and is ready for production hardening (TLS, buffering, power management, and geofencing).

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 is the main objective of the project described in the article?




Question 2: Which device is used in the project for GSM connectivity?




Question 3: What programming environment is recommended for this project?




Question 4: Which GNSS module is mentioned in the article?




Question 5: What is required for internet connectivity in the project?




Question 6: Which operating systems are supported for this project?




Question 7: What is the purpose of the HTTP endpoint in the project?




Question 8: Which safety practice is mentioned in the article?




Question 9: What is the recommended way to upload code to the MKR GSM 1400?




Question 10: What is the minimum Python version required for this project?




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

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

Follow me:
error: Contenido Protegido / Content is protected !!
Scroll to Top