-
Notifications
You must be signed in to change notification settings - Fork 1.7k
Javascript‐Programming
The INAV Configurator includes a JavaScript transpiler that allows you to program flight controller logic conditions using JavaScript instead of raw logic condition commands. This provides a modern development experience with IntelliSense, syntax highlighting, and real-time validation.
The JavaScript transpiler converts JavaScript code into INAV logic conditions, enabling you to program flight controller behavior using familiar JavaScript syntax.
Real-time autocomplete with type information and documentation
Clear error messages with line numbers and suggestions
const { flight, override } = inav;
// Increase VTX power when far from home
if (flight.homeDistance > 500) {
override.vtx.power = 4;
}
Complete example showing VTX power control based on distance
- Transpiler: JavaScript → INAV Logic Conditions
- Decompiler: INAV Logic Conditions → JavaScript
- Round-trip capable: Code survives transpile/decompile cycles
- Monaco Editor: Full-featured code editor with syntax highlighting
- IntelliSense: Context-aware autocomplete with documentation
- Real-time Validation: Immediate feedback on syntax errors
- Error Messages: Clear, actionable messages with line numbers
All INAV Operations Supported:
- Arithmetic operations (
+,-,*,/,%) - Comparison and logical operations (
>,<,===,&&,||,!) - Math functions (
Math.min(),Math.max(),Math.sin(),Math.cos(),Math.tan(),Math.abs()) - Flow control (
edge(),sticky(),delay(),timer(),whenChanged()) - Variable management (
gvar[0-7],let,var) - RC channel access and state detection (
rc[n].value,rc[n].low,rc[n].mid,rc[n].high) - Flight parameter overrides (
override.vtx.*,override.throttle, etc.) - Flight mode detection (
flight.mode.poshold,flight.mode.rth, etc.) - PID controller outputs (
pid[0-3].output) - Waypoint navigation
JavaScript Features:
-
constdestructuring:const { flight, override } = inav; -
letvariables: variables with a lifetime of that loop only -
varvariables: allocated to global variables for long lifetime - Arrow functions:
() => condition - Object property access:
flight.altitude,rc[0].value
Use if statements for conditions that check and execute every cycle:
const { flight, override } = inav;
// Checks every cycle - adjusts VTX power continuously
if (flight.homeDistance > 100) {
override.vtx.power = 3;
}Use when: You want the action to happen continuously while the condition is true.
Use edge() for actions that should execute only once when a condition becomes true:
const { flight, gvar, edge } = inav;
// Executes ONCE when armTimer reaches 1000ms
edge(() => flight.armTimer > 1000, { duration: 0 }, () => {
gvar[0] = flight.yaw; // Save initial heading
gvar[1] = 0; // Initialize counter
});Parameters:
- condition: Function returning boolean
- duration: Minimum duration in ms (0 = instant, >0 = debounce)
- action: Function to execute once
Use when:
- Initializing on arm
- Detecting events (first time RSSI drops)
- Counting discrete occurrences
- Debouncing noisy signals
Use sticky() for conditions that latch ON and stay ON until reset.
Option 1: Variable assignment syntax (recommended when you need to reference the latch state):
const { flight, override, gvar, sticky } = inav;
// Create a latch that turns ON when RSSI < 30, OFF when RSSI > 70
var rssiWarning = sticky({
on: () => flight.rssi < 30,
off: () => flight.rssi > 70
});
// Use the latch variable to control actions
if (rssiWarning) {
override.vtx.power = 4; // Max power while latched
}The latch variable can be referenced multiple times:
const { flight, override, gvar, sticky } = inav;
var lowBatteryLatch = sticky({
on: () => flight.cellVoltage < 330,
off: () => flight.cellVoltage > 350
});
// Use the latch variable to control multiple actions
if (lowBatteryLatch) {
override.throttleScale = 50;
gvar[0] = 1; // Warning flag
}Option 2: Callback syntax (simpler when actions are self-contained):
const { flight, sticky, override } = inav;
// Latch ON when RSSI < 30, OFF when RSSI > 70
sticky(
() => flight.rssi < 30, // ON condition
() => flight.rssi > 70, // OFF condition
() => {
override.vtx.power = 4; // Executes while latched
}
);Use when:
- Warning states that need manual reset
- Hysteresis/deadband behavior
- Failsafe conditions
Use delay() to execute after a condition has been true for a duration:
const { flight, gvar, delay } = inav;
// Executes only if RSSI < 30 for 2 seconds continuously
delay(() => flight.rssi < 30, { duration: 2000 }, () => {
gvar[0] = 1; // Set failsafe flag
});Use when:
- Avoiding false triggers
- Requiring sustained conditions
- Timeouts and delays
Use timer() for actions that toggle ON and OFF periodically:
const { gvar, timer } = inav;
// Toggle gvar[0] every second: ON for 1000ms, OFF for 1000ms
timer(1000, 1000, () => {
gvar[0] = 1; // Active during ON phase
});Use when:
- Blinking indicators
- Periodic sampling
- Timed sequences
Use whenChanged() to detect when a value changes by a threshold:
const { flight, gvar, whenChanged } = inav;
// Trigger when altitude changes by >= 10m within 100ms
whenChanged(flight.altitude, 10, () => {
gvar[0] = gvar[0] + 1; // Count altitude changes
});Use when:
- Detecting significant value changes
- Monitoring sensor variations
- Change-based triggers
-
+,-,*,/,%(modulus)
-
===,>,<(standard comparisons) -
approxEqual(a, b, tolerance)- approximate equality with tolerance
-
&&,||,!(standard logical operators) -
xor(a, b)- exclusive OR -
nand(a, b)- NOT AND -
nor(a, b)- NOT OR
-
Math.min(a, b)- minimum of two values -
Math.max(a, b)- maximum of two values -
Math.sin(degrees)- sine (takes degrees, not radians) -
Math.cos(degrees)- cosine (takes degrees) -
Math.tan(degrees)- tangent (takes degrees) -
Math.abs(x)- absolute value
-
mapInput(value, maxValue)- scales from [0:maxValue] to [0:1000] -
mapOutput(value, maxValue)- scales from [0:1000] to [0:maxValue]
Example:
// Scale RC throttle (1000-2000) to normalized (0-1000)
const normalized = mapInput(rc[3].value - 1000, 1000);
// Scale normalized (0-1000) to servo angle (0-180)
const servoAngle = mapOutput(normalized, 180);// RC channel value (1000-2000us)
if (rc[1].value > 1500) {
gvar[0] = 1;
}
// RC channel state detection
if (rc[1].low) { // < 1333us
gvar[1] = 1;
}
if (rc[1].mid) { // 1333-1666us
gvar[2] = 1;
}
if (rc[1].high) { // > 1666us
gvar[3] = 1;
}Runtime state that persists across logic condition evaluations:
// Global variables (runtime state, 8 slots)
gvar[0] = 100;
gvar[1] = gvar[1] + 1; // CounterCompile-time named expressions that make code more readable:
const { flight, override } = inav;
// Define reusable calculations with meaningful names
let distanceThreshold = 500;
let altitudeLimit = 100;
let combinedCheck = flight.homeDistance > distanceThreshold && flight.altitude > altitudeLimit;
if (combinedCheck) {
override.vtx.power = 4;
}Benefits:
- Makes code self-documenting with meaningful names
- Compiler automatically optimizes duplicate expressions
- Variable names preserve through compile/decompile cycles
Important: let/const are compile-time substituted, not runtime variables. For runtime state, use gvar[].
Allocated to gvar slots automatically:
// Var variables (allocated to gvar slots)
var counter = 0;
counter = counter + 1;Note: Variable names are stored in Configurator. Loading from FC to a different computer will use default names. Save your scripts in a text editor when upgrading INAV or switching computers.
Variables can also be renamed by right-click on the variable.
Conditional value assignment in a single expression:
const { flight, override } = inav;
// Choose value based on condition
let throttleLimit = flight.cellVoltage < 330 ? 25 : 50;
if (flight.cellVoltage < 350) {
override.throttleScale = throttleLimit;
}
// Inline ternary
override.vtx.power = flight.homeDistance > 500 ? 4 : 2;
// Nested ternary for multiple conditions
let powerLevel = flight.rssi < 30 ? 4 :
flight.rssi < 50 ? 3 :
flight.rssi < 70 ? 2 : 1;const { override } = inav;
// VTX control
override.vtx.power = 4; // Power level (0-4)
override.vtx.band = 5; // Band (0-5)
override.vtx.channel = 7; // Channel (0-8)
// Throttle control
override.throttle = 1500; // Direct throttle (1000-2000)
override.throttleScale = 75; // Scale percentage (0-100)
// Arming safety
override.armSafety = 1; // Override arming checksCheck which flight modes are currently active:
const { flight, gvar, override } = inav;
// Check specific flight modes
if (flight.mode.poshold === 1) {
gvar[0] = 1; // Flag: in position hold
}
if (flight.mode.rth === 1) {
override.vtx.power = 4; // Max power during RTH
}
if (flight.mode.failsafe === 1) {
gvar[7] = 1; // Emergency flag
}Available flight modes:
-
flight.mode.failsafe- Failsafe mode -
flight.mode.manual- Manual/passthrough mode -
flight.mode.rth- Return to home -
flight.mode.poshold- Position hold -
flight.mode.cruise- Cruise mode -
flight.mode.althold- Altitude hold -
flight.mode.angle- Angle/self-level mode -
flight.mode.horizon- Horizon mode -
flight.mode.air- Air mode -
flight.mode.acro- Acro mode -
flight.mode.courseHold- Course hold -
flight.mode.waypointMission- Waypoint mission active -
flight.mode.user1throughflight.mode.user4- User-defined modes
INAV has 4 programming PID controllers (configured in the Programming PID tab). You can read their output values in JavaScript:
const { pid, gvar, override } = inav;
// Read PID controller outputs
if (pid[0].output > 500) {
override.throttle = 1600;
}
// Store PID output for OSD display
gvar[0] = pid[0].output;
// Combine multiple PID outputs
gvar[1] = pid[0].output + pid[1].output;PID controllers:
-
pid[0].outputthroughpid[3].output- Output values from the 4 programming PID controllers
Note: PID controller parameters (setpoint, measurement, gains) are configured in the Programming PID tab, not in JavaScript. The JavaScript code can only read the output values.
Q: Which pattern should I use?
- Use
iffor continuous control (checking every cycle) - Use
edge()for one-time actions when condition becomes true - Use
sticky()for latching conditions with hysteresis - Use
delay()for actions that need sustained conditions - Use
timer()for periodic toggling - Use
whenChanged()for detecting value changes
Q: How do I debug my code?
Use global variables to track state:
const { flight, gvar, edge } = inav;
// Initialize debug counter
edge(() => flight.armTimer > 1000, { duration: 0 }, () => {
gvar[7] = 0; // Use gvar[7] as debug counter
});
// Increment on each event
edge(() => flight.rssi < 30, { duration: 0 }, () => {
gvar[7] = gvar[7] + 1;
});
// Check gvar[7] value in OSD or ConfiguratorQ: What's the difference between let and var?
-
letthe variable goes away after each loop (implemented via compile-time expression substitution) -
varvariables are allocated to gvar slots (keep their values between loops)
Q: How many global variables can I use?
INAV has 8 global variables: gvar[0] through gvar[7]. Each can store values from -1,000,000 to 1,000,000.
Q: Can I use regular JavaScript functions?
specific INAV functions are supported (edge(), sticky(), delay(), timer(), whenChanged(), and Math functions). The transpiler converts JavaScript to INAV logic conditions, which have specific supported operations.
const { flight, gvar, edge } = inav;
edge(() => flight.armTimer > 1000, { duration: 0 }, () => {
gvar[0] = 0; // Reset counter
gvar[1] = flight.yaw; // Save heading
gvar[2] = flight.altitude; // Save starting altitude
});const { flight, gvar, edge } = inav;
// Initialize counter on arm
edge(() => flight.armTimer > 1000, { duration: 0 }, () => {
gvar[0] = 0;
});
// Count each time RSSI drops below 30
edge(() => flight.rssi < 30, { duration: 100 }, () => {
gvar[0] = gvar[0] + 1;
});![RC Override Example]
const { flight, override } = inav;
// Far away - maximum power
if (flight.homeDistance > 500) {
override.vtx.power = 4;
}
// Medium distance
if (flight.homeDistance > 200 && flight.homeDistance <= 500) {
override.vtx.power = 3;
}
// Close to home - reduce power
if (flight.homeDistance <= 200) {
override.vtx.power = 2;
}const { flight, gvar, sticky, override } = inav;
// Latch warning at 3.3V/cell, clear at 3.5V/cell
var lowVoltageWarning = sticky({
on: () => flight.cellVoltage < 330, // Warning threshold
off: () => flight.cellVoltage > 350 // Recovery threshold
});
if (lowVoltageWarning) {
override.throttleScale = 50; // Reduce throttle
gvar[0] = 1; // Warning flag
}const { flight, override, edge } = inav;
// Only trigger if RSSI < 30 for at least 500ms
edge(() => flight.rssi < 30, { duration: 500 }, () => {
override.vtx.power = 4;
});const { rc, gvar } = inav;
// Detect specific stick position combination
if (rc[1].low && rc[2].mid && rc[3].high) {
gvar[0] = 1; // Special mode activated
}const {
flight, // Flight telemetry (altitude, speed, GPS, battery, etc.)
override, // Override flight parameters (VTX, throttle, arming)
rc, // RC channels (rc[1-18].value, .low, .mid, .high)
gvar, // Global variables (gvar[0-7])
pid, // Programming PID controller outputs (pid[0-3].output)
waypoint, // Waypoint navigation info
edge, // Edge detection function
sticky, // Latching condition function
delay, // Delayed execution function
timer, // Periodic timer function
whenChanged // Change detection function
} = inav;The flight object includes a mode sub-object for checking active flight modes:
-
flight.mode.poshold,flight.mode.rth,flight.mode.althold, etc.
-
Initialize variables on arm using
edge()withflight.armTimer > 1000 - Use gvars for state - they persist between logic condition evaluations
- edge() duration = 0 means instant trigger on condition becoming true
- edge() duration > 0 adds debounce time
- if statements are continuous - they execute every cycle
- sticky() provides hysteresis - prevents rapid ON/OFF switching
- All trig functions take degrees, not radians
- RC channels: 0-17 (18 channels total)
- Global variables: -1,000,000 to 1,000,000 range
INAV 9.0: JavaScript programming introduced
- All INAV logic condition operations supported
- RC channel state detection (LOW/MID/HIGH)
- XOR/NAND/NOR logical operations
- Approximate equality with tolerance
- MAP_INPUT/MAP_OUTPUT scaling functions
- Timer and change detection functions
- Flight mode detection (
flight.mode.poshold,flight.mode.rth, etc.) - PID controller output access (
pid[0-3].output) - Named parameter syntax for sticky with variable assignment
- IntelliSense and real-time validation
Related Pages:
- Programming Tab - How to use the Programming tab
- Logic Conditions - Traditional logic condition programming
Last Updated: 2025-12-10
INAV Version Release Notes
8.0.0 Release Notes
7.1.0 Release Notes
7.0.0 Release Notes
6.0.0 Release Notes
5.1 Release notes
5.0.0 Release Notes
4.1.0 Release Notes
4.0.0 Release Notes
3.0.0 Release Notes
2.6.0 Release Notes
2.5.1 Release notes
2.5.0 Release Notes
2.4.0 Release Notes
2.3.0 Release Notes
2.2.1 Release Notes
2.2.0 Release Notes
2.1.0 Release Notes
2.0.0 Release Notes
1.9.1 Release notes
1.9.0 Release notes
1.8.0 Release notes
1.7.3 Release notes
Older Release Notes
QUICK START GUIDES
Getting started with iNav
Fixed Wing Guide
Howto: CC3D flight controller, minimOSD , telemetry and GPS for fixed wing
Howto: CC3D flight controller, minimOSD, GPS and LTM telemetry for fixed wing
INAV for BetaFlight users
launch mode
Multirotor guide
YouTube video guides
DevDocs Getting Started.md
DevDocs INAV_Fixed_Wing_Setup_Guide.pdf
DevDocs Safety.md
Connecting to INAV
Bluetooth setup to configure your flight controller
DevDocs Wireless Connections (BLE, TCP and UDP).md\
Flashing and Upgrading
Boards, Targets and PWM allocations
Upgrading from an older version of INAV to the current version
DevDocs Installation.md
DevDocs USB Flashing.md
Setup Tab
Live 3D Graphic & Pre-Arming Checks
Calibration Tab
Accelerometer, Compass, & Optic Flow Calibration
Alignment Tool Tab
Adjust mount angle of FC & Compass
Ports Tab
Map Devices to UART Serial Ports
Receiver Tab
Set protocol and channel mapping
Mixer Tab
Set aircraft type and how its controlled
Outputs Tab
Set ESC Protocol and Servo Parameters
Modes Tab
Assign flight modes to transmitter switches
Standard Modes
Navigation Modes
Return to Home
Fixed Wing Autolaunch
Auto Launch
Configuration Tab
No wiki page currently
Failsafe Tab
Set expected behavior of aircraft upon failsafe
PID Tuning
Navigation PID tuning (FW)
Navigation PID tuning (MC)
EZ-Tune
PID Attenuation and scaling
Tune INAV PID-FF controller for fixedwing
DevDocs Autotune - fixedwing.md
DevDocs INAV PID Controller.md
DevDocs INAV_Wing_Tuning_Masterclass.pdf
DevDocs PID tuning.md
DevDocs Profiles.md
OSD and VTx
DevDocs Betaflight 4.3 compatible OSD.md
OSD custom messages
OSD Hud and ESP32 radars
DevDocs OSD.md
DevDocs VTx.md
LED Strip
DevDocs LedStrip.md
Programming
DevDocs Programming Framework.md
Adjustments
DevDocs Inflight Adjustments.md
Mission Control
iNavFlight Missions
DevDocs Safehomes.md
MultiWii Serial Protocol
MSP V2
MSP Messages reference guide
MSP Navigation Messages
INAV MSP frames changelog
Telemetry
INAV Remote Management, Control and Telemetry
MAVlink Control and Telemetry
Lightweight Telemetry (LTM)
Tethered Logging
Log when FC is connected via USB
Blackbox
DevDocs Blackbox.md
INAV blackbox variables
DevDocs USB_Mass_Storage_(MSC)_mode.md
CLI
iNav CLI variables
DevDocs Cli.md
DevDocs Settings.md
VTOL
DevDocs MixerProfile.md
DevDocs VTOL.md
TROUBLESHOOTING
"Something" is disabled Reasons
Blinkenlights
Sensor auto detect and hardware failure detection
Pixel OSD FAQs
TROUBLESHOOTING
Why do I have limited servo throw in my airplane
ADTL TOPICS, FEATURES, DEV INFO
AAT Automatic Antenna Tracker
Building custom firmware
Default values for different type of aircrafts
Source Enums
Features safe to add and remove to fit your needs.
Developer info
Making a new Virtualbox to make your own INAV[OrangeRX LRS RX and OMNIBUS F4](OrangeRX-LRS-RX-and-OMNIBUS-F4)
Rate Dynamics
Target and Sensor support
Ublox 3.01 firmware and Galileo
DevDocs Controls
DevDocs 1wire.md
DevDocs ADSB.md
DevDocs Battery.md
DevDocs Buzzer.md
DevDocs Channel forwarding.md
DevDocs Display.md
DevDocs Fixed Wing Landing.md
DevDocs GPS_fix_estimation.md
DevDocs LED pin PWM.md
DevDocs Lights.md
DevDocs OSD Joystick.md
DevDocs Servo Gimbal.md
DevDocs Temperature sensors.md
OLD LEGACY INFO
Supported boards
DevDocs Boards.md
Legacy Mixers
Legacy target ChebuzzF3
Legacy target Colibri RACE
Legacy target Motolab
Legacy target Omnibus F3
Legacy target Paris Air Hero 32
Legacy target Paris Air Hero 32 F3
Legacy target Sparky
Legacy target SPRacingF3
Legacy target SPRacingF3EVO
Legacy target SPRacingF3EVO_1SS
DevDocs Configuration.md
Request form new PRESET
DevDocs Introduction.md
Welcome to INAV, useful links and products
UAV Interconnect Bus
DevDocs Rangefinder.md
DevDocs Rssi.md
DevDocs Runcam device.md
DevDocs Serial.md
DevDocs Telemetry.md
DevDocs Rx.md
DevDocs Spektrum bind.md
DevDocs INAV_Autolaunch.pdf