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
  • Flight Controller Setup
  • Ark Flow Configuration
  1. Sensor
  2. ARK Flow

PX4 Instructions

PreviousArdupilot InstructionsNext3D models & Case files

Last updated 6 months ago

Hardware Setup

Wiring

Mounting

The recommended mounting orientation is with the connectors on the board pointing towards back of vehicle, as shown in the following picture.

Firmware Setup

  • Firmware target: ark_can-flow_default

  • Bootloader target: ark_can-flow_canbootloader

Flight Controller Setup

INFO

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

Enable DroneCAN

The steps are:

  • Connect ARK Flow CAN to the Pixhawk CAN.

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

PX4 Configuration

Set the following parameters in QGroundControl:

Ark Flow Configuration

On the ARK Flow, you may need to configure the following parameters:

Parameter
Description

CAN built-in bus termination.

The ARK Flow is connected to the CAN bus using a Pixhawk standard 4 pin JST GH cable. For more information, refer to the instructions.

ARK Flow align with Pixhawk

This corresponds to the default value (0) of the parameter . Change the parameter appropriately if using a different orientation.

The sensor can be mounted anywhere on the frame, but you will need to specify the focal point position, relative to vehicle centre of gravity, during .

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

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

In order to use the ARK Flow board, connect it to the Pixhawk CAN bus and enable the UAVCAN 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 .

You need to set the EKF optical flow parameters to enable fusing optical flow measurements for velocity calculation, set necessary parameters, and define offsets if the sensor is not centred within the vehicle.

Enable optical flow fusion by setting .

To optionally disable GPS aiding, set to 0.

Enable .

Enable .

Set to 10.

Set to 0.2.

Set to 0.08.

Set to 30.

Set to 0.08.

Set to 25.

Set to 7.4 to match the PAW3902 maximum angular flow rate.

The parameters , and can be set to account for the offset of the Ark Flow from the vehicle centre of gravity.

CAN Wiring
SENS_FLOW_ROT
PX4 configuration
PX4 DroneCAN Firmware
dynamic node allocation
PX4 DroneCAN Firmware > Building the Firmware
UAVCAN_ENABLE
DroneCAN ESCs
UAVCAN_ENABLE
Finding/Updating Parameters
DroneCAN > Enabling DroneCAN
DroneCAN
EKF2_OF_CTRL
EKF2_GPS_CTRL
UAVCAN_SUB_FLOW
UAVCAN_SUB_RNG
EKF2_RNG_A_HMAX
EKF2_RNG_QLTY_T
UAVCAN_RNG_MIN
UAVCAN_RNG_MAX
SENS_FLOW_MINHGT
SENS_FLOW_MAXHGT
SENS_FLOW_MAXR
EKF2_OF_POS_X
EKF2_OF_POS_Y
EKF2_OF_POS_Z
CANNODE_TERM
ARK Flow | PX4 Guide (main)
Most up to date PX4 Documentation
Logo