Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/Ardupilot/ardupilot/llms.txt

Use this file to discover all available pages before exploring further.

DroneCAN (formerly UAVCAN v1/v0) is a lightweight, publish-subscribe protocol designed for reliable communication over CAN bus in aerospace and robotics systems. ArduPilot’s AP_DroneCAN library implements the full DroneCAN stack, including dynamic node allocation, parameter exchange, and ESC/servo output over the bus. The companion AP_CANManager library owns the physical CAN interfaces and dispatches frames to the correct protocol driver.

Robust Bus Topology

CAN bus provides differential signalling and hardware error detection, making it more noise-immune than UART-based peripherals in electrically noisy environments.

Plug-and-Play Nodes

Dynamic Node Allocation (DNA) lets new CAN peripherals join the bus without manual node-ID configuration. The flight controller acts as the DNA server.

Rich Peripheral Ecosystem

Supported peripherals include GPS/compass modules, ESCs, airspeed sensors, battery monitors, rangefinders, RGB LEDs, and buzzers.

AP_Periph Firmware

Any board running ArduPilot can become a CAN peripheral using the AP_Periph firmware, enabling custom sensor integration over DroneCAN.

Architecture overview

┌──────────────────────────────────┐
│          ArduPilot vehicle        │
│                                  │
│  AP_CANManager                   │
│  ├── CAN interface 0 (CAN_P1_*)  │
│  │     └── AP_DroneCAN driver    │  ← protocol driver instance 1
│  └── CAN interface 1 (CAN_P2_*)  │
│        └── AP_DroneCAN driver    │  ← protocol driver instance 2
│                                  │
│  AP_DroneCAN                     │
│  ├── DNA Server (node allocation)│
│  ├── Publisher: ESC commands     │
│  ├── Publisher: servo commands   │
│  ├── Publisher: LED/buzzer       │
│  └── Subscriber: GPS, compass,   │
│       airspeed, battery, ...     │
└──────────┬───────────────────────┘
           │  CAN bus (120 Ω terminated)
    ┌──────┴──────────────────────────┐
    │  Peripheral nodes               │
    │  • GPS+compass module (node 10) │
    │  • ESC #1 (node 20)             │
    │  • ESC #2 (node 21)             │
    │  • Airspeed sensor (node 30)    │
    └─────────────────────────────────┘

AP_CANManager

AP_CANManager initialises the hardware CAN interfaces and registers protocol drivers against them. It is a singleton accessible as AP::can().
class AP_CANManager {
public:
    void init(void);
    bool register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver);
    AP_CANDriver* get_driver(uint8_t i) const;
    AP_CAN::Protocol get_driver_type(uint8_t i) const;
    uint8_t get_num_drivers(void) const;
    void log_text(LogLevel loglevel, const char *tag, const char *fmt, ...);
};

CAN interface parameters

Each physical CAN port is configured with a CAN_Pn_* parameter group where n is the port index (1-based):
ParameterDescription
CAN_P1_DRIVERDriver instance to assign to this interface (1 = first driver, 2 = second)
CAN_P1_BITRATEBus bitrate in bits/s (default 1 000 000)
CAN_P1_FDBITRATECAN-FD data-phase bitrate (0 = disable FD mode)
CAN_P2_DRIVERDriver instance for the second physical interface

AP_DroneCAN

AP_DroneCAN is a driver that implements the DroneCAN protocol on top of the libcanard stack. Multiple driver instances can run simultaneously (one per physical interface or paired interfaces).
class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend {
public:
    static AP_DroneCAN *get_dronecan(uint8_t driver_index);

    void init(uint8_t driver_index) override;
    bool add_interface(AP_HAL::CANIface *can_iface) override;
    bool prearm_check(char *fail_msg, uint8_t fail_msg_len) const;

    void SRV_push_servos(void);               // send servo positions
    bool led_write(uint8_t led_index,
                   uint8_t red, uint8_t green, uint8_t blue);
    void set_buzzer_tone(float frequency, float duration_s);

    bool set_parameter_on_node(uint8_t node_id, const char *name,
                                float value, ParamGetSetFloatCb *cb);
    bool get_parameter_on_node(uint8_t node_id, const char *name,
                                ParamGetSetFloatCb *cb);
    bool save_parameters_on_node(uint8_t node_id, ParamSaveCb *cb);

    void send_reboot_request(uint8_t node_id);
};

DroneCAN driver parameters

ParameterDescription
CAN_D1_PROTOCOLProtocol for driver 1. See the protocol table below.
CAN_D1_UC_NODEThis autopilot’s DroneCAN node ID (1–127; 0 = auto)
CAN_D1_UC_ESC_BMBitmask of servo channels routed to DroneCAN ESCs
CAN_D1_UC_SRV_BMBitmask of servo channels routed to DroneCAN servos
CAN_D1_UC_OPTIONOptions bitmask (see below)

Protocol values for CAN_Dn_PROTOCOL

ValueProtocolNotes
0NoneInterface disabled
1DroneCANStandard DroneCAN (UAVCAN v0)
4PiccoloCANCurrawong Piccolo ESC protocol
6EFI_NWPMUNWPMU EFI controller
7USD1USD1 rangefinder
8KDECANKDE Direct ESC protocol
10ScriptingLua scripting access
11BenewakeBenewake rangefinder
Values 2, 3, 5, and 9 are reserved (previously used protocols that have been removed). Do not reuse them.

Dynamic Node Allocation (DNA)

When a new peripheral powers on without a configured node ID, it broadcasts an allocation request. The AP_DroneCAN_DNA_Server (running on the flight controller) responds with a unique node ID chosen from the range 1–127. Assignments are stored persistently so that the same peripheral always receives the same ID after a power cycle.
Peripheral              AP_DroneCAN_DNA_Server
    │── Allocation request (CAN message) ──▶│
    │◀── Allocation response (node_id=20) ──│
    │                                        │
    │ (peripheral now uses node ID 20)        │

DNA options bitmask (CAN_D1_UC_OPTION)

BitOptionEffect
0DNA_CLEAR_DATABASEClear stored node assignments on next boot
1DNA_IGNORE_DUPLICATE_NODEDo not warn on duplicate node IDs
2CANFD_ENABLEDEnable CAN-FD mode on this driver
3DNA_IGNORE_UNHEALTHY_NODEIgnore nodes reporting unhealthy status
4USE_ACTUATOR_PWMSend servo output as ActuatorCommand instead of raw PWM
5SEND_GNSSRe-broadcast GNSS fix from flight controller onto the bus

ESC output over DroneCAN

When CAN_D1_UC_ESC_BM is set, AP_DroneCAN::SRV_send_esc() publishes uavcan.equipment.esc.RawCommand messages at the rate configured by CAN_D1_UC_SRV_RT (Hz). Each bit in the bitmask enables one ESC channel.
CAN_D1_UC_ESC_BM = 0b00001111   ← ESC channels 1-4 sent over DroneCAN
CAN_D1_UC_SRV_BM = 0b11110000   ← servo channels 5-8 sent as ActuatorCommand
Mix DroneCAN ESCs with conventional PWM ESCs freely — only the channels in the bitmask are sent over CAN. Channels not in the mask continue to use the standard servo/ESC output system.

Supported peripheral types

DroneCAN GPS modules publish uavcan.equipment.gnss.Fix2 and optionally uavcan.equipment.gnss.Auxiliary. Many modules also include a magnetometer published as uavcan.equipment.ahrs.MagneticFieldStrength2. These are detected and consumed by AP_GPS_DroneCAN and the compass subsystem automatically.
DroneCAN ESCs receive uavcan.equipment.esc.RawCommand (throttle values, –8192 to +8191 scaled from the servo output range). They reply with uavcan.equipment.esc.Status carrying RPM, voltage, current, and temperature. ArduPilot consumes this via the ESC telemetry backend.
Airspeed sensors publish uavcan.equipment.air_data.IndicatedAirspeed and uavcan.equipment.air_data.StaticPressure. Detected by AP_Airspeed_DroneCAN.
Battery nodes publish uavcan.equipment.power.BatteryInfo. Detected by AP_BattMonitor_DroneCAN. Set BATTn_MONITOR = 8 to enable.
Rangefinder nodes publish uavcan.equipment.range_sensor.Measurement. Detected by AP_RangeFinder_DroneCAN. Set RNGFNDn_TYPE = 24 to enable.
AP_DroneCAN::led_write() publishes uavcan.equipment.indication.LightsCommand. set_buzzer_tone() publishes uavcan.equipment.indication.BeepCommand. Both are driven by the AP_Notify system automatically.

Parameter exchange

The DroneCAN parameter protocol allows the flight controller to read and write parameters on any node. This is used during configuration and by the SLCAN pass-through for GUI tools.
// Read a float parameter from node 20
AP_DroneCAN *dronecan = AP_DroneCAN::get_dronecan(0);
if (dronecan) {
    AP_DroneCAN::ParamGetSetFloatCb cb = FUNCTOR_BIND_MEMBER(
        &MyClass::param_cb, bool,
        AP_DroneCAN *, const uint8_t, const char *, float &);
    dronecan->get_parameter_on_node(20, "ESC_THR_CURVE", &cb);
}

// Write a parameter and save
dronecan->set_parameter_on_node(20, "ESC_THR_CURVE", 0.5f, &cb);
dronecan->save_parameters_on_node(20, &save_cb);

AP_Periph: custom CAN peripheral firmware

AP_Periph (located in Tools/AP_Periph/) is a stripped-down ArduPilot build that runs on small CAN nodes. It re-uses the same sensor drivers (AP_GPS, AP_Compass, AP_Baro, etc.) but outputs data over DroneCAN rather than MAVLink. To create a custom CAN peripheral:
  1. Add your sensor driver to the AP_Periph build in Tools/AP_Periph/.
  2. Define the DroneCAN message publisher in the peripheral’s main loop.
  3. Flash the peripheral board with the resulting firmware.
  4. On the flight controller, set CAN_D1_PROTOCOL = 1 and CAN_P1_DRIVER = 1.
AP_Periph boards must have proper 120 Ω bus termination resistors at each end of the CAN bus. Missing termination causes reflections that produce intermittent communication failures which are difficult to diagnose.

Wiring and setup checklist

  1. Termination — 120 Ω resistors at both physical ends of the bus.
  2. Bitrate — All nodes must use the same bitrate (default 1 Mbit/s via CAN_P1_BITRATE).
  3. Driver assignment — Set CAN_P1_DRIVER = 1 and CAN_D1_PROTOCOL = 1 for DroneCAN.
  4. Node IDs — Leave CAN_D1_UC_NODE = 0 (auto) unless you have a reason to assign a fixed ID.
  5. Peripheral type — Set the appropriate *_TYPE parameter for each peripheral class (e.g. GPS_TYPE = 9 for DroneCAN GPS).
  6. Reboot — CAN initialisation happens at boot; a reboot is required after changing CAN_* parameters.

Build docs developers (and LLMs) love