Skip to content

DroneCAN

DroneCAN is a open software communication protocol for flight controllers and other CAN devices on a vehicle to communicate with each other.

WARNING

  • DroneCAN is not enabled by default, and nor are specific sensors and features that use it. For setup information see PX4 Configuration.
  • PX4 requires an SD card to enable dynamic node allocation and for firmware update. The SD card is not used in flight.

INFO

DroneCAN was previously known as UAVCAN v0 (or just UAVCAN). The name was changed in 2022.

Benefits of DroneCAN

Connecting peripherals over DroneCAN has many benefits:

  • Many different sensors and actuators are already supported.
  • CAN has been specifically designed to deliver robust and reliable connectivity over relatively large distances. It enables safe use of ESCs on bigger vehicles and communication redundancy.
  • The bus is bi-directional, enabling health monitoring, diagnostics, and RPM telemetry.
  • Wiring is less complicated as you can have a single bus for connecting all your ESCs and other DroneCAN peripherals.
  • Setup is easier as you configure ESC numbering by manually spinning each motor.
  • It allows users to configure and update the firmware of all CAN-connected devices centrally through PX4.

Supported Hardware

Most common types of peripherals (sensors, ESCs, and servos) that are DroneCAN/UAVCAN v0 compliant are supported.

Supported hardware includes (this is not an exhaustive list):

Hardware Setup

DroneCAN operates over a CAN network. DroneCAN hardware should be connected as described in CAN > Wiring.

Node ID Allocation

Every DroneCAN device must be configured with a node id that is unique on the vehicle.

Most devices support Dynamic Node Allocation (DNA), which allows PX4 to automatically configure the node ID of each detected peripheral on system startup. Consult the manufacturer documentation for details on whether your device supports DNA and how to enable it. Many devices will automatically switch to DNA if the node id is set to 0. PX4 will enable the built in allocation server if the UAVCAN_ENABLE parameter is > 1 (set to 2 or 3).

Some devices don't support DNA. Additionally, in certain mission-critical scenarios, you might prefer to manually configure node IDs beforehand instead of relying on the dynamic allocation server. If you wish to disable the DNA completely, set UAVCAN_ENABLE to 1 and manually set each node ID to a unique value. If the DNA is still running and certain devices need to be manually configured, give these devices a value greater than the total number of DroneCAN devices to avoid clashes.

The PX4 node ID can be configured using the UAVCAN_NODE_ID parameter. The parameter is set to 1 by default.

WARNING

At time of writing, PX4 does not run the node allocation server on the CAN2 port. This means that if you have a device that is only connected to CAN2 (not redundantly to CAN1 and CAN2), you will need to manually configure its node ID.

PX4 Configuration

DroneCAN is configured on PX4 by setting specific PX4 parameters in QGroundControl. You will need to enable DroneCAN itself, along with subscriptions and publications for any features that you use.

In some cases you may need to also configure parameters on the connected CAN devices (these can also be set using QGC).

Enabling DroneCAN

To enable the PX4 DroneCAN driver, set the UAVCAN_ENABLE parameter:

  • 0: DroneCAN driver disabled
  • 1: DroneCAN driver enabled for sensors, DNA server disabled
  • 2: DroneCAN driver enabled for sensors, DNA server enabled
  • 3: DroneCAN driver enabled for sensors and ESCs, DNA server enabled

2 or 3 are recommended, if DNA is supported.

DroneCan Subscriptions & Publications

PX4 does not publish or subscribe to DroneCAN messages that might be needed by default, in order to avoid spamming the CAN bus. Instead you must enable publication or subscription to the messages associated with a particular feature by setting the associated UAVCAN parameter.

Sensor parameters may not exist (be visible in QGC) until you have enabled the associated DroneCAN sensor subscription!

For example, SENS_FLOW_MINHGT does not exist until UAVCAN_SUB_FLOW is enabled.

For example, to use a connected DroneCAN smart battery you would enable the UAVCAN_SUB_BAT parameter, which would subscribe PX4 to receive BatteryInfo DroneCAN messages. If using a peripheral that needs to know if PX4 is armed, you would need to set the UAVCAN_PUB_ARM parameter so that PX4 starts publishing ArmingStatus messages.

The parameter names are prefixed with UAVCAN_SUB_ and UAVCAN_PUB_ to indicate whether they enable PX4 subscribing or publishing. The remainder of the name indicates the specific message/feature being set.

DroneCAN peripherals connected to PX4 can also be configured using parameters via QGC. By convention, parameters named with the prefix CANNODE_ have prefined meaning, and may be documented in the parameter reference. CANNODE_ parameters prefixed with CANNODE_PUB_ and CANNODE_SUB_ enable the peripheral to publish or subscribe the associated DroneCAN message. These allow DroneCAN peripherals to be configured to only subscribe and publish messages that they actually need (in the same way that PX4 uses the corresponding UAVCAN_PUB_/UAVCAN_SUB_ parameters). Note that a peripheral might might not use CANNODE_ parameters, in which case it may have to publish/subscribe to particular messages whether or not they are needed.

The following sections provide additional detail on the PX4 and DroneCAN peripheral parameters used to enable particular features.

Sensors

The DroneCAN sensor parameters/subscriptions that you can enable are (in PX4 v1.14):

GPS

PX4 DroneCAN parameters:

GPS CANNODE parameter (set using QGC):

Other PX4 Parameters:

RTK GPS

Set the same parameters as for GPS above. In addition, you may also need to set the following parameters depending on whether your RTK setup is Rover and Fixed Base, or Rover and Moving Base, or both.

Rover and Fixed Base

Position of 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:

Rover module parameters (also set using QGC):

You could instead use UAVCAN_PUB_MBD and CANNODE_SUB_MBD, which also publish RTCM messages (these are newer). Using the RTCMStream message means that you can implement moving base (see below) at the same time.

Rover and Moving Base

As discussed in RTK GPS Heading with Dual u-blox F9P a vehicle can have two RTK modules in order to calculate yaw from GPS. In this setup the vehicle has a moving base RTK GPS and a rover RTK GPS.

These parameters can be set on moving base and rover RTK CAN nodes, respectively:

For PX4 you will also need to set GPS_YAW_OFFSET to indicate the relative position of the moving base and rover: 0 if your Rover is in front of your Moving Base, 90 if Rover is right of Moving Base, 180 if Rover is behind Moving Base, or 270 if Rover is left of Moving Base.

Barometer

PX4 DroneCAN parameters:

Compass

PX4 DroneCAN parameters:

Distance Sensor/Range Finder

PX4 DroneCAN parameters:

Other PX4 parameters:

  • If the rangefinder is not positioned at the vehicle centre of gravity you can account for the offset using EKF2_RNG_POS_X, EKF2_RNG_POS_Y and EKF2_RNG_POS_Z.
  • Other EKF2_RNG_* parameters may be relevant, in which case they should be documented with the specific rangefinder.

Optical Flow Sensor

PX4 DroneCAN parameters:

Other PX4 parameters:

Optical flow sensors require rangefinder data. However the rangefinder need not be part of the same module, and if not, may not be connected via DroneCAN. If the rangefinder is connected via DroneCAN (whether inbuilt or separate), you will also need to enable it as described in the rangefinder section (above).

Arming Peripherals

PX4 DroneCAN parameters:

ESC & Servos

DroneCAN ESCs and servos require the motor order and servo outputs to be configured.

QGC CANNODE Parameter Configuration

QGroundControl can inspect and modify parameters belonging to CAN devices attached to the flight controller, provided the device are connected to the flight controller before QGC is started.

CAN nodes are displayed separate sections in Vehicle Settings > Parameters named Component X, where X is the node ID. For example, the screenshot below shows the parameters for a CAN GPS with node id 125 (after the Standard, System, and Developer parameter groupings).

QGC Parameter showing selected DroneCAN node

Device Specific Setup

Most DroneCAN nodes require no further setup, unless specifically noted in their device-specific documentation.

Firmware Update

PX4 can upgrade device firmware over DroneCAN. To upgrade the device, all you need to do is copy the firmware binary into the root directory of the flight controller's SD card and reboot.

Upon boot the flight controller will automatically transfer the firmware onto the device and upgrade it. If successful, the firmware binary will be removed from the root directory and there will be a file named XX.bin in the /ufw directory of the SD card.

Troubleshooting

Q: My DroneCAN devices aren't working.

A: Check that the UAVCAN_ENABLE parameter is set correctly. To see a list of devices/nodes that PX4 has detected on the CAN bus, open NSH (i.e. go to the QGroundControl MAVLink Console) and type uavcan status.


Q: The DNA server isn't giving out node IDs.

A: PX4 requires an SD card to perform dynamic node allocation. Make sure you have (a working) one inserted and reboot.


Q: The motors aren't spinning when armed.

A: Make sure UAVCAN_ENABLE is set to 3 to enable DroneCAN ESC output.


Q: The motors don't spin until throttle is increased.

A: Use Acutator > Actuator Testing to confirm that the motor outputs are set to the correct minimum values.