Research Log: Implementing Optical Flow & LiDAR for GPS-Denied Autonomy in iNav
At the Atom Aviation R&D Lab, we are constantly pushing the envelope of what unmanned systems can achieve. While GPS navigation is standard for outdoor long-range missions, true autonomy requires robust performance in “GPS-denied” environments—indoors, under heavy canopy, or in urban canyons.
As an Electronics and Communication Engineer, I approach this challenge not just as a pilot, but as a systems integrator. The goal? To achieve a stable, locked-in loiter without relying on satellite triangulation. To do this, we need to implement Sensor Fusion—specifically, integrating Optical Flow (for horizontal velocity estimation) and Time-of-Flight (ToF) LiDAR (for vertical precision).
In this technical log, I’ll detail the integration of the MicroAir MTF-01 module into the iNav flight control ecosystem.
The Hardware Architecture: MicroAir MTF-01
For this development cycle, I selected the MicroAir MTF-01. From an ECE perspective, this module is an efficient package. It combines two critical sensors on a single PCB:
-
PMW3901 Optical Flow Sensor: Acts similarly to a high-speed DSP camera, tracking surface texture to calculate $V_x$ and $V_y$ (horizontal velocity).
-
ToF Rangefinder (LiDAR): Emits IR pulses to measure distance ($Z_{alt}$) with much higher resolution and update rates (100Hz) than a standard barometric pressure sensor.
Key Technical Specs:
-
Interface: UART (Universal Asynchronous Receiver-Transmitter)
-
Protocol: MSP (MultiWii Serial Protocol)
-
Operating Voltage: 5V DC
-
Power Dissipation: ~500mW
For our testbed platform, I am utilizing a modified Cinebot25 frame, retrofitted with a Flywoo GN745 V3 AIO. We specifically need an FC with available hardware UART resources to handle the high-speed telemetry stream from the sensor.
Step 1: Protocol Handshake & Firmware Configuration
The MTF-01 often ships with a default configuration for Mavlink (Ardupilot/PX4). Since our current architecture runs on iNav, we need to reconfigure the sensor’s MCU to output MSP.
The Procedure:
Using a USB-to-TTL (FTDI) converter, I interfaced the sensor directly with the MicoAssistant debugging tool.
-
Baud Rate: 115200 bps (Standard for this telemetry bandwidth).
-
Output Protocol: Switched from
MicrolinktoMSP.
Engineering Note: Without this protocol mismatch correction, the Flight Controller’s CPU (STM32) will receive uninterpretable packets, leading to a communication bus error.
Step 2: UART Interfacing & Signal Integrity
In embedded systems, proper wiring is non-negotiable. I interfaced the sensor to a spare hardware UART (UART 4) on the Flight Controller.
Pinout Logic:
-
VCC (5V): Connected to the FC’s BEC (Battery Eliminator Circuit). Crucial: Ensure the voltage rail is stable; ripples in power can cause noise in the Optical Flow data.
-
GND: Common ground reference.
-
TX (Sensor) $\rightarrow$ RX (FC): Transmits velocity/distance data.
-
RX (Sensor) $\rightarrow$ TX (FC): Receives initialization commands.
Mounting Considerations: The sensor was mounted on the ventral side of the chassis. I ensured the optical lens had a clear Field of View (FOV) and verified that the landing gear provided >2cm clearance to prevent initialization errors during the boot sequence.
Step 3: iNav System Configuration
With the hardware layer sorted, we move to the logic layer in the iNav Configurator.
-
I/O Setup: In the Ports tab, I enabled MSP on UART 4.
-
Sensor Definition: In the Configuration tab, I mapped the
Optical FlowandRangefinderinputs to the MSP bus. -
Verification: A reboot is required. Upon restart, the “Flow” and “Sonar” status indicators turned Blue, confirming a successful handshake between the peripheral and the main CPU.
Step 4: Control Loop Tuning (PID & Filters)
This is where the R&D background plays a massive role. The default navigation PIDs in iNav are generalized. For a tight indoor hold using this specific sensor, we need to tune the controller parameters in the CLI (Command Line Interface).
We are essentially adjusting the gain on the Velocity ($V$) and Position ($P$) feedback loops.
Bash
# Vertical Velocity (Z-axis) Gains - Critical for Altitude Hold
set nav_mc_vel_z_p = 150
set nav_mc_vel_z_i = 250
set nav_mc_vel_z_d = 25
# Horizontal Position/Velocity (XY-axis) Gains - Critical for Loiter
set nav_mc_pos_xy_p = 80
set nav_mc_vel_xy_p = 50
set nav_mc_vel_xy_i = 40
set nav_mc_vel_xy_d = 60
# Sensor Fusion Parameters
set debug_mode = FLOW_RAW
set inav_allow_dead_reckoning = ON # Allows EKF to use Flow when GPS is null
set inav_max_surface_altitude = 200 # Max effective range of ToF in cm
save
Step 5: Calibration & Data Validation
Before flight, we must validate the data orientation. If the sensor is rotated relative to the FC, the feedback loop will be positive (destabilizing) instead of negative (stabilizing).
The “Bench Test”:
Using the Sensors tab, I analyzed the raw data stream:
-
Pitching the drone forward: Confirmed Optical Flow Y-axis response.
-
Rolling the drone right: Confirmed Optical Flow X-axis response.
I also performed the Optical Flow Scaling procedure, hovering the drone at a known altitude to calibrate the pixel-shift-to-distance ratio. A scale factor between 4.0 and 6.0 is optimal for this CMOS sensor.
Conclusion: The Engineering Verdict
After successful integration and tuning at the Atom Aviation facility, the results were distinct. The drone achieved a “Surface Mode” lock, maintaining XYZ coordinates with high precision without a single GPS satellite connection.
By leveraging the MTF-01 and understanding the communication protocols and control theory behind it, we have successfully upgraded a standard FPV rig into a platform capable of autonomous indoor inspection.
Ready for the next sprint.
Anurag Chauhan
Electronics & Communication Engineer
R&D Division, Atom Aviation


GEPRC EM4218 350KV Motor