name: olfactory-navigation
description: >
Interprets a time-ordered buffer of Scentience OPU sensor readings to classify
plume contact state (approaching, turbulent contact, signal loss,
near-source), then recommends a navigation action with calibrated confidence.
Use when controlling a robot or UAV through an odor plume, recovering from
signal loss, following a chemical gradient, or evaluating real-time olfactory
source localization.
version: 1.0.0
author: kordelfrance
license: Apache 2.0
compatibility: >
Works with raw JSON readings from the scentience BLE or Sockets API. No
additional SDK install required for interpretation. Use the ble-device skill
to acquire readings. Optional: scentience Navigation Environment
(gym-compatible) for simulation and RL.
metadata:
domain: olfaction
tags:
- navigation
- plume-tracking
- source-localization
- robotics
- uav
- gradient
- casting
hardware:
- Reconnaisscent
- Scentinel
depends_on:
- ble-device
related_papers:
- 'Chasing Ghosts: A Sim2Real Olfactory Navigation Stack (arXiv 2026)'
- >-
Emergent Behavior in Evolutionary Swarms for Machine Olfaction (ACM GECCO
2024)
- 'AI and Olfaction: A Survey on the Sense of Smell for Robotics (ChemRxiv)'
Goal
Given a sliding window of Scentience OPU readings, classify the robot's current plume interaction state and emit a structured navigation recommendation — including action, confidence, and reasoning — suitable for direct consumption by a motor controller or higher-level planner.
Instructions
1. Buffer Readings
Accumulate a sliding window of N readings (N = 10–30 depending on polling rate).
Extract the target compound. Use VOC as the default; substitute a specific compound
(e.g., NH3, H2S) when tracking a known chemical source.
from collections import deque
window = deque(maxlen=30)
async for reading in device.stream_ble(async_=True):
if reading["STATUS_opuA"] != "active":
continue
window.append(reading)
if len(window) >= 10:
result = analyze_plume(window, compound="VOC")
controller.act(result)
2. Compute Signal Features
import numpy as np
def extract_features(window, compound: str, noise_floor: float = 0.02):
signal = [r[compound] for r in window]
# Baseline correction — rolling minimum over the window
baseline = min(signal)
normalized = [max(0.0, s - baseline) for s in signal]
n = len(normalized)
recent = normalized[max(0, n - 3):]
prior = normalized[max(0, n - 10): max(0, n - 3)]
short_trend = np.mean(recent) / (np.mean(prior) + 1e-6)
long_trend = float(np.polyfit(range(n), normalized, 1)[0])
intermittency = sum(1 for s in normalized if s > noise_floor) / n
peak_snr = (max(normalized) - np.mean(normalized)) / (np.std(normalized) + 1e-6)
return {
"short_trend": short_trend,
"long_trend": long_trend,
"intermittency": intermittency,
"peak_snr": peak_snr,
"mean_signal": float(np.mean(normalized)),
}
| Feature | Meaning |
|---|---|
short_trend |
Ratio of recent 3-reading mean to prior 7-reading mean |
long_trend |
Linear slope over the full window (positive = strengthening) |
intermittency |
Fraction of readings above detection threshold |
peak_snr |
Signal quality; values < 2 indicate noise-dominated readings |
3. Classify Plume State
Apply this decision matrix (order matters — evaluate top-to-bottom, take the first match):
| State | Trigger conditions | Physical interpretation |
|---|---|---|
NEAR_SOURCE |
intermittency > 0.7 AND short_trend < 1.15 |
Saturating; likely within source region |
APPROACHING |
short_trend > 1.2 AND long_trend > 0 |
Signal strengthening; moving toward source |
CONTACT_TURBULENT |
intermittency > 0.4 AND peak_snr > 2 |
Inside plume; turbulent filament contact |
LOST_PLUME |
intermittency < 0.15 (after prior contact) |
Plume exit or plume shifted |
UNKNOWN |
None of the above | Insufficient or noisy signal |
def classify_state(features, had_prior_contact: bool) -> str:
f = features
if f["intermittency"] > 0.7 and f["short_trend"] < 1.15:
return "NEAR_SOURCE"
if f["short_trend"] > 1.2 and f["long_trend"] > 0:
return "APPROACHING"
if f["intermittency"] > 0.4 and f["peak_snr"] > 2:
return "CONTACT_TURBULENT"
if f["intermittency"] < 0.15 and had_prior_contact:
return "LOST_PLUME"
return "UNKNOWN"
Apply state hysteresis: require 3 consecutive readings in a new state before transitioning. Single-frame transitions are treated as noise.
4. Map State to Navigation Action
| State | recommended_action |
Notes |
|---|---|---|
APPROACHING |
"advance" |
Maintain heading; increase sampling rate |
CONTACT_TURBULENT |
"hold_and_cast" |
Hold position; lateral sweeps to center on filament |
LOST_PLUME |
"cast_upwind" |
Crosswind casting with upwind bias; expand search radius |
NEAR_SOURCE |
"slow_and_densify" |
Reduce speed; increase spatial sampling density |
UNKNOWN |
"hold" |
Wait for window to fill; do not act on ambiguous state |
If wind vector is available (ENV_* fields or external anemometer), bias cast_upwind
direction using atan2(wind_y, wind_x). Without wind data, cast orthogonally to the
last known heading.
5. Format Output
{
"timestamp_ms": 1743379215000,
"compound": "VOC",
"plume_contact_confidence": 0.82,
"state": "APPROACHING",
"trend": "increasing",
"signal_pattern": "sustained_gradient",
"source_proximity_hypothesis": "moderate",
"recommended_action": "advance",
"confidence": 0.78,
"reasoning_summary": "Short-term signal ratio 1.34 and positive long-term slope (+0.021 ppm/frame) indicate movement toward source. Intermittency 0.55 consistent with structured plume contact. Confidence 0.78.",
"window_size": 22,
"features": {
"short_trend": 1.34,
"long_trend": 0.021,
"intermittency": 0.55,
"peak_snr": 4.1
}
}
Confidence is derived from peak_snr × intermittency. Values below 0.5 indicate
ambiguous state — treat recommended_action as tentative and pass this to the
controller with reduced authority.
Examples
Signal loss — recovery casting
Window (VOC, normalized): [0.82, 0.91, 0.78, 0.12, 0.08, 0.05, 0.04, 0.06, 0.03, 0.04]
↑ plume exit
Features: intermittency=0.30, peak_snr=1.1, short_trend=0.61
State → LOST_PLUME
recommended_action → "cast_upwind"
reasoning → "Intermittency dropped from 0.80 to 0.30 over 7 frames after prior contact.
Begin crosswind casting with upwind bias. Expand search radius by 0.5 m
per cast arm."
Near-source saturation
Window (VOC, normalized): [1.2, 1.8, 2.4, 2.9, 2.8, 3.1, 2.9, 3.0, 3.1, 2.8]
Features: intermittency=0.90, short_trend=1.02, peak_snr=1.4
State → NEAR_SOURCE
recommended_action → "slow_and_densify"
reasoning → "High sustained signal (mean 2.62 ppm normalized), intermittency 0.90,
short-term ratio 1.02 indicates plateau. Likely within 1–3 m of source
region. Reduce speed to 0.1 m/s; increase sampling to 10 Hz."
Turbulent contact in crosswind
Window (VOC, normalized): [0.0, 0.9, 0.0, 1.2, 0.0, 0.8, 0.0, 1.1, 0.0, 0.7]
Features: intermittency=0.50, peak_snr=5.2, short_trend=0.92
State → CONTACT_TURBULENT
recommended_action → "hold_and_cast"
reasoning → "Alternating high/zero pattern (peak_snr 5.2) indicates turbulent filament
contact. Hold position; execute ±0.3 m lateral casts to locate filament
center before advancing."
Constraints
- Signal loss ≠ source absence — Turbulent plumes produce intermittent contact.
LOST_PLUMEtriggers recovery casting, not mission abort. - Do not act on single spikes — One reading above threshold is noise until
peak_snr > 2andintermittency > 0.2over at least 5 frames. - Absolute concentration is unreliable — Use baseline-corrected normalized values only. Raw ppm varies by temperature, humidity, sensor age, and cross-sensitivity.
- State hysteresis is required — Three consecutive readings must confirm a new state before transitioning. Single-frame state flips indicate noise.
- Sensor warm-up — Discard readings from the first 60 s after device power-on.
- Wind data improves decisions — Without wind vector, casting is orthogonal to last
heading. With wind vector, bias upwind using available
ENV_*or anemometer data. - This skill produces recommendations, not commands — The downstream controller
decides whether to execute. Always forward
confidenceso the controller can apply authority scaling (e.g., ignore actions when confidence < 0.4). - Plume Environment (simulation) — For training and evaluation, use the Scentience
Plume Environment sandbox (
gym.make("scentience/PlumeEnv-v0")), which provides ground-truth plume state for reward shaping.