ARK X20 RTK GPS
ARK X20 RTK GPS is an open source DroneCAN RTK GPS, u-blox ZED-X20P all-band high precision GNSS module, magnetometer, barometer, IMU, buzzer, and safety switch module.

Where to Buy
Order this module from:
- ARK Electronics (US)
Hardware Specifications
- Open Source Schematic and BOM
- Sensors
- Ublox ZED-X20P
- All-band all constellation GNSS receiver
- Best position accuracy and availability in different environments
- RTK, PPP-RTK and PPP algorithms expanding the limits of performance
- Highest quality GNSS raw data
- u-blox end-to-end hardened security
- 25Hz update rate
- ST IIS2MDC Magnetometer
- Bosch BMP390 Barometer
- Invensense ICM-42688-P 6-Axis IMU
- Ublox ZED-X20P
- STM32F412VGH6 MCU
- Safety Button
- Buzzer
- Two Pixhawk Standard CAN Connectors (4 Pin JST GH)
- X20 “UART 2” Connector
- 4 Pin JST GH
- TX, RX, PPS, GND
- I2C Expansion Connector
- 4 Pin JST-GH
- 5.0V, SCL, SDA, GND
- Pixhawk Standard Debug Connector (6 Pin JST SH)
- LED Indicators
- Safety LED
- GPS Fix
- RTK Status
- RGB system status
- USA Built
- Power Requirements
- 5V
- 144mA Average
- 157mA Max
Hardware Setup
Wiring
The ARK X20 RTK GPS is connected to the CAN bus using a Pixhawk standard 4 pin JST GH cable. For more information, refer to the CAN Wiring instructions.
Mounting
The recommended mounting orientation is with the connectors on the board pointing towards the back of vehicle.
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during PX4 configuration.
Firmware Setup
ARK X20 RTK GPS runs the PX4 cannode firmware. As such, it supports firmware update over the CAN bus and dynamic node allocation.
ARK X20 RTK GPS boards ship with recent firmware pre-installed, but if you want to build and flash the latest firmware yourself, refer to the cannode firmware build instructions.
Firmware target: ark_can-rtk-gps_default Bootloader target: ark_can-rtk-gps_canbootloader
Flight Controller Setup
Enabling DroneCAN
In order to use the ARK X20 RTK GPS, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter UAVCAN_ENABLE to 2 for dynamic node allocation (or 3 if using DroneCAN ESCs).
The steps are:
- In QGroundControl set the parameter UAVCAN_ENABLE to
2or3and reboot (see Finding/Updating Parameters). - Connect ARK X20 RTK GPS CAN to the Pixhawk CAN.
Once enabled, the module will be detected on boot. GPS data should arrive at 10Hz.
PX4 Configuration
You need to set necessary DroneCAN parameters and define offsets if the sensor is not centred within the vehicle:
- Enable GPS yaw fusion by setting bit 3 of EKF2_GPS_CTRL to true.
- Enable GPS blending to ensure the heading is always published by setting SENS_GPS_MASK to 7 (all three bits checked).
- Enable UAVCAN_SUB_GPS, UAVCAN_SUB_MAG, and UAVCAN_SUB_BARO.
- The parameters EKF2_GPS_POS_X, EKF2_GPS_POS_Y and EKF2_GPS_POS_Z can be set to account for the offset of the ARK X20 RTK GPS from the vehicles centre of gravity.
ARK X20 RTK GPS Configuration
You may need to configure the following parameters on the ARK X20 RTK GPS itself:
| Parameter | Description |
|---|---|
| CANNODE_NODE_ID | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| CANNODE_TERM | CAN built-in bus termination. Set to 1 if this is the last node on the CAN bus. |
Setting Up Rover and Fixed Base
Position of the rover is established using RTCM messages from the RTK base module (the base module is connected to QGC, which sends the RTCM information to PX4 via MAVLink).
PX4 DroneCAN parameters:
- UAVCAN_PUB_RTCM:
- Makes PX4 publish RTCM messages (RTCMStream) to the bus (which it gets from the RTK base module via QGC).
Rover module parameters (also set using QGC):
- CANNODE_SUB_RTCM tells the rover that it should subscribe to RTCMStream RTCM messages on the bus (from the moving base).
INFO
Use UAVCAN_PUB_MBD and CANNODE_SUB_MBD instead if you want to implement moving base (see below) at the same time.
For more information see Rover and Fixed Base in the DroneCAN guide.
LED Meanings
The GPS status lights are located to the right of the connectors
- Blinking green is GPS fix
- Blinking blue is received corrections and RTK Float
- Solid blue is RTK Fixed
The CAN status lights are located top the left of the connectors
- Slow blinking green is waiting for CAN connection
- Fast blinking green is normal operation
- Slow blinking green and blue is CAN enumeration
- Fast blinking blue and red is firmware update in progress
- Blinking red is error
- If you see a red LED there is an error and you should check the following
- Make sure the flight controller has an SD card installed
- Make sure the ARK X20 RTK GPS has
ark_can-rtk-gps_canbootloaderinstalled prior to flashingark_can-rtk-gps_default - Remove binaries from the root and ufw directories of the SD card and try to build and flash again
- If you see a red LED there is an error and you should check the following
See Also
- ARK X20 RTK GPS Documentation (ARK Docs)