Hobbywing CAN ESCs


Recieved some newly released Hobbywing X8 G2 motors / ESCs and I’m trying to make it work over CAN using PX4 with a Cube Orange Plus, but was not successful.

I am able to set up the motors using Ardupilot and their Hobbywing guide:

For some reason, they come configured with 500k baudrate but after following the ardpilot docs I’ve set it to 1M baudrate but I’m still not able to get CAN to work on PX4 with them.

According to their website they say they work with PX4 but there is no documentation about CAN usage.

Any help/tips using CAN on PX4 for hobbywing ESCs or how to diagonose/test CAN on PX4 is greatly appriciated.

Ah okey, so there isn’t Hobbywing CAN support yet but it’s being worked on.

According to the X8 G2 FAQ it can be configured to DRONECAN and work with PX4 if you get their DATALINK adapter and program it

I’ve just bought the module emailed their support for more info. Will update post after testing

Thanks. If you can get a datasheet and drop it in the PR that would help. It sucks having drivers for proprietary hardware and no datasheet to refer back to when we’re a few years down the road.

I’ll ask for it aswell

I would like to share my experience configuring Hobbywing X8 G2 ESCs for CAN usage, in case this helps clarify the current state of protocol support and tooling.

Hardware / tools used:

  • Hobbywing X8 G2 ESCs

  • Hobbywing Datalink V2 (latest firmware)

  • ESC firmware updated to latest version

  • Pixhawk 6X flight controller

  • DroneCAN GUI + ArduPilot for testing

Observations:

  1. Using the Hobbywing Datalink software, I was NOT able to find any option to switch the ESC protocol from Hobbywing CAN to DroneCAN.

    • The CAN tuning tab is not very user-friendly.

    • ESCs were not displayed properly in the list.

    • I was only able to change CAN ID and throttle ID there.

  2. I then installed ArduPilot and followed the official Hobbywing DroneCAN setup guide:
    https://ardupilot.org/copter/docs/common-hobbywing-dronecan-esc.html

  3. Even after following the tutorial, the ESCs were NOT detected initially.

  4. The critical missing step for me was:

    In the Hobbywing panel, I had to change
    Throttle Source = PWM → CAN

    Only after changing this:

    • ESCs immediately detected throttle signal

    • ESC beeping stopped

    • CAN communication became active

Because of this, I am currently unsure what Hobbywing documentation means when it states that the CAN protocol can be switched from Hobbywing CAN to DroneCAN via the Datalink adapter.

From my testing:

  • I could configure CAN IDs

  • I could enable CAN throttle source

  • but I could NOT find any explicit “protocol switch” setting.

It would be helpful if documentation clarified:

  • whether X8 G2 actually supports true DroneCAN mode

  • whether protocol switching is automatic

  • or whether ArduPilot performs compatibility handling internally.

Hope this helps.

Thanks for the detailed info Anton.

I was also able to set the X8 G2 up on Ardupilot using the ardupilot documentation.
I am emailing back and forth with Hobbywing, I’ll let them know your suggestions.

Were you able to get them working on PX4?

If possible could you provide the Datalink software (windows installer)?

Had a shot at the DATALINK software, and it’s really bad.
No instructions, no option for DRONECAN that I can see.

Still waiting for a response from Hobbywing.

Okey, I got it working, but it wasn’t straightforward.

  1. DATALINK software has to be FW 2.16 or higher or it wouldn’t connect to my X8 G2. Mine arrived with 2.09 when I received it Feb 2026.
    • The Datalink dongle can be upgraded with the DATALINK software (see video)
  2. DATALINK can set the CAN protocol form HWCAN (hobbywing can) → DRONECAN (UAVCAN that px4 uses).
    • The software is all in chinese so which buttons to “scan”/“connect”/“save” are not obivious, see video for more help.
  3. PX4 CAN implementation on 1.16 (not sure about others) doesn’t feature a settable parameter for Disarmed value, it has UAVCAN_EC_MIN /_MAX and _FAIL, but not disarmed. This causes the ESCs to not make the “connected and ready” beep sound when connected to PX4 after boot. Only after arming once do they stop their “idle beeping” and allow throttle.
    • Running uavcan status shows that the default disarm value is 65535, why this is implemented like this I am not sure. I would assume 0 would be a logical default value, so I compiled my own version with slight code change that sets disarm to 0 by default and it worked, connected automattically now on boot and is able to throttle after arming. This is not shown in the video since I discovered this after.

@anton_anufriev See above if you want to try and setup with PX4

The code fix is litterly a one line to src/drivers/uavcan/module.yaml
Can anyone think of a reason why this shouldn’t be included?
For the Servos it exists.

Perhaps @Jake1 give his opinion.

  output_groups:
    - param_prefix: UAVCAN_EC
      group_label: 'ESCs'
      channel_label: 'ESC'
      standard_params:
        disarmed: { min: 0, max: 8191, default: 0 }    // Fix, line added
        min: { min: 0, max: 8191, default: 1 }
        max: { min: 0, max: 8191, default: 8191 }
        failsafe: { min: 0, max: 8191 }
      num_channels: 8
    - param_prefix: UAVCAN_SV
      group_label: 'Servos'
      channel_label: 'Servo'
      standard_params:
        disarmed: { min: 0, max: 1000, default: 500 }
        min: { min: 0, max: 1000, default: 0 }
        max: { min: 0, max: 1000, default: 1000 }
        failsafe: { min: 0, max: 1000 }
      num_channels: 8

Did some testing on 1.17 today and found that the issue is resolved on 1.17 so no need for the change I proposed above.

There were fixes made by @dakejahl

1. 6a1cefd7 — "uavcan: esc: fix uavcan ESC control" (Jul 2025)

  The main fix. Previously, the RawCommand message was published with zero channels when disarmed
  (trimmed trailing zeros via _max_number_of_nonzero_outputs). Some ESCs interpret an empty message as
  an error state. This commit:
  - Removed the DISARMED_OUTPUT_VALUE (UINT16_MAX) sentinel logic
  - Always publishes the correct number of channels based on configured UAVCAN_EC_FUNCx params
  - On the CANnode receiver side, zero commands now map to NAN (disarmed) instead of 0.0f which mixers
  could interpret as actual throttle
2. 30fcb4fc — "uavcan: esc: init msg to avoid publishing random values" (Aug 2025)

  A one-liner — zero-initializes the RawCommand struct:
  -  uavcan::equipment::esc::RawCommand msg;
  +  uavcan::equipment::esc::RawCommand msg = {};
  Without this, the first published message could contain stack garbage as throttle values.

Do you have an updated version of the HW Datalink software? I can only find the old one from 2020 online and HW support has not gotten back to me yet. Thanks.

Yes, I’ll post tomorrow

1 Like

Hey any updates on this? I’d appreciate anything.

Sorry, forgot to respond, here is firmware which I used https://drive.google.com/file/d/179hGsvFFEzqCrvBVBq0xpxDq9AGxMbOh/view?usp=sharing

Thank you so much. You’re a lifesaver.

1 Like

And remeber on 1.17 the UAVCAN buggs with startup are fixed!