GPS Switching
Theseus provides a Lua script to enable automatic switching between GPS and VPS.
The script has been tested in a jammed environment. It is not expected to perform auto switching in a spoofed environment.
Micro VPS appears as a GPS to ArduPilot. If you followed our recommended parameter setup, VPS should be configured as GPS 2 and your real GPS as GPS 1 on ArduPilot.
Upload the script below to ArduPilot to enable auto switching:
Jamming Detection
The script employs high level heuristics to determine whether jamming is present on GPS 1:
Number of satellites < 16: fewer satellites indicate likely jamming.
HDOP > 160: high spatial concentration of origin satellites.
Horizontal, vertical, speed accuracy: low accuracy (high values) are also indicators of poor satellite geometry or interference in the signal path.
local MIN_NUM_SATS_GPS1 = 16
local MAX_HDOP_GPS1 = 160
local MAX_HORIZONTAL_ACCURACY_GPS1 = 5
local MAX_VERTICAL_ACCURACY_GPS1 = 8
local MAX_SPEED_ACCURACY_GPS1 = 1.8These heuristics have been tested against air defense jammers in Eastern Ukraine.
Switching Logic
The script will automatically try to use the GPS (GPS 1) if it is available. If GPS is not healthy, it will switch to VPS (GPS 2). If GPS becomes healthy again, the script will switch back to GPS.
If the user manually disables either sources of position, the script will not switch into it. For example, if the user disables VPS, the script will stay on GPS.
If both sources of position are unhealthy and/or manually disabled, the ArduPilot GPS backend is disabled using DISABLE_GPS_RC_OPTION.
Configuring RC Switches
The script also assumes that two RC switches are configured: one for GPS 1 and one for GPS 2. These RC switches can be used by the operator to manually enable or disable either GPS sources in the Lua script.
Select which channels (RCX) you intend on using for these manual switches (e.g., RC7 and RC11), and set the corresponding option to 300 (GPS 1) and 301 (for GPS 2).
You also need to set SCR_USER1=1 to enable these switches.
For example:
RC7_OPTION = 300, RC7 controls the GPS 1 switch
RC11_OPTION = 301, RC11 controls the GPS 2 switch
If the switch is latched, the corresponding GPS will be deactivated in the Lua script and the source switched to the other GPS.
Note: The Scripting RCx_OPTION values in ArduPilot are hardcoded within the GPS Switching Lua script. If you are using multiple Lua scripts on the same flight controller, make sure that those scripts do not use Scripting1 or Scripting2 (RCx_OPTION = 300, 301, respectively).
Last updated
