ARK Documentation
  • ARK Electronics Docs
  • Embedded Computers
    • ARK Just A Jetson
      • Pinout
      • Block Diagram
      • Flashing Guide
      • 3D Model
  • Flight Controller
    • ARK FPV
      • Pinout
      • PX4 Instructions
      • ArduPilot Instructions
      • Betaflight Instructions
      • Bootloader Flashing Using DFU
      • 3D Models
    • ARKV6X
      • PX4 Instructions
      • ArduPilot Instructions
      • 3D Models
    • ARK Pixhawk Autopilot Bus Carrier
      • 3D Models and Case Files
      • Pinout
      • PX4 Instructions
    • ARK Jetson PAB Carrier
      • Getting Started
      • Block Diagram
      • Pinout
      • 3D Models and Case Files
      • Flashing Guide
      • ARK Software
        • Services
      • Autopilot Connections
      • Updating the Flight Controller Firmware
      • Micro USB Console
      • Power Cycling USB Ports
      • Mini DisplayPort
      • USB Wi-Fi Adapters
      • USB Bluetooth Adapters
    • ARK Pi6X Flow
      • Block Diagram
      • Pinout
      • 3D Models
      • Flashing Guide
        • Pi CM4 Lite with Micro SD
        • Pi CM4 with EMMC
        • After Flashing, Before Installing
        • Wi-Fi Setup
        • SSH
      • ARK Software
        • Services
      • Autopilot Connections
      • Updating the Flight Controller Firmware
    • ARK VOXL2 RTK PAB Carrier
      • Pinout
      • Connectors and Cables
      • 3D Models
      • Autopilot Connections
  • Electronic Speed Controller
    • ARK 4IN1 ESC
      • Pinout
      • Firmware
      • PWM Calibration
      • 3D Models
  • Radio
    • ARK M.2 LTE
      • OpenVPN
    • ARK Microhard DDL Carrier
      • 3D Model
  • Sensor
    • ARK Flow
      • Ardupilot Instructions
      • PX4 Instructions
      • 3D models & Case files
    • ARK Flow MR
      • Ardupilot Instructions
      • PX4 Instructions
      • 3D models & Case files
    • ARK CANnode
      • PX4 Instructions
      • 3D Models
  • GPS
    • ARK GPS
      • PX4 Instructions
      • 3D Models
    • ARK MOSAIC-X5 RTK GPS
    • ARK RTK Base
      • 3D Model
    • ARK RTK GPS
    • ARK TESEO GPS
    • ARK SAM GPS
      • PX4 Instructions
      • Ardupilot Instructions
      • Betaflight Instructions
      • 3D Model
  • Power
    • ARK PAB Power Module
      • PX4 Instructions
      • ArduPilot Instructions
      • 3D Model
    • ARK 12S PAB Power Module
      • PX4 Instructions
      • ArduPilot Instructions
      • 3D Model
  • IMU
    • ARK ADIS16507
      • PX4 Instructions
      • ArduPilot Instructions
      • 3D Model
    • ARK SCH16T
      • PX4 Instructions
      • ArduPilot Instructions
      • 3D Model
  • ROS2 & PX4
    • Mastering Precision Landing with PX4 & ROS2
    • Aruco Detectios Tutorial
    • Custom Modes Hardware Demo with PX4 & ROS2
    • Utilizing Custom Modes in PX4 with ROS2 and QGC
    • Simulated Offboard Mode
  • PX4 Log Encryption
  • Radio Integration
    • Doodle Labs Nimble Integration Guide for ARK Jetson PAB Carrier
  • Resources
    • Links
    • About
Powered by GitBook
On this page
  • Hardware Setup
  • Firmware Setup
  • PX4 Configuration
  1. GPS
  2. ARK GPS

PX4 Instructions

PreviousARK GPSNext3D Models

Last updated 3 months ago

Find most up to date documentation at

Hardware Setup

Wiring

The ARK GPS is connected to the CAN bus using a Pixhawk standard 4 pin JST GH cable. For more information, refer to the 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 center of gravity, during .

Firmware Setup

ARK GPS runs the . As such, it supports firmware update over the CAN bus and .

ARK GPS boards ship with recent firmware pre-installed, but if you want to build and flash the latest firmware yourself see .

  • Firmware target: ark_can-gps_default

  • Bootloader target: ark_can-gps_canbootloader

PX4 Configuration

You need to set necessary parameters and define offsets if the sensor is not centered within the vehicle. The required settings are outlined below.

INFO

The ARK GPS will not boot if there is no SD card in the flight controller when powered on.

Enable DroneCAN

The steps are:

  • Connect ARK GPS CAN to the Pixhawk CAN.

Once enabled, the module will be detected on boot. GPS data should arrive at 10Hz.

Sensor Position Configuration

If the sensor is not centered within the vehicle you will also need to define sensor offsets:

In order to use the ARK GPS board, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter to 2 for dynamic node allocation (or 3 if using ).

In QGroundControl set the parameter to 2 or 3 and reboot (see ).

DroneCAN configuration in PX4 is explained in more detail in .

Enable GPS yaw fusion by setting bit 3 of to true.

Enable , , and .

Set to 1 if this is that last node on the CAN bus.

The parameters , and can be set to account for the offset of the ARK GPS from the vehicles centre of gravity.

https://docs.px4.io/main/en/dronecan/ark_gps.html
CAN Wiring
PX4 configuration
PX4 DroneCAN Firmware
dynamic node allocation
PX4 DroneCAN Firmware > Building the Firmware
DroneCAN
UAVCAN_ENABLE
DroneCAN ESCs
UAVCAN_ENABLE
Finding/Updating Parameters
DroneCAN > Enabling DroneCAN
EKF2_GPS_CTRL
UAVCAN_SUB_GPS
UAVCAN_SUB_MAG
UAVCAN_SUB_BARO
CANNODE_TERM
EKF2_GPS_POS_X
EKF2_GPS_POS_Y
EKF2_GPS_POS_Z