VESC DroneCAN Telemetry for Dynamic Notch

Hi,

I am running two VESC 100/250 ESCs driving two 28 pole (14 pole pair) motors on a CAN bus using UAVCAN v0 and would like to use the reported telemetry for the dynamic notch. The VESC ESCs report eletrical RPM and it seems like ArduPilot expects mechanical RPM.

Used HW & SW:
2x VESC 100/250 with FW 5.3
CubeOrange with ArduCopter 4.3.0 (branch with some modifications)

Initially i tried the following parameters
INS_HNTCH_ENABLE = 1
INS_HNTCH_MODE = 3
INS_HNTCH_FREQ = 30
INS_HNTCH_BW = 25
INS_HNTCH_ATT = 30
INS_HNTCH_REF = 1
INS_HNTCH_HMNCS = 1
and in the dataflash log FTN.NF1 is exactly 14 * ESC.RPM.
Hoping to be able to do the conversion manually, similar to what is apparently done with BLheli motors using SERVO_BLH_POLES, I set INS_HNTCH_REF = 1/14, so all relevant params
INS_HNTCH_ENABLE = 1
INS_HNTCH_MODE = 3
INS_HNTCH_FREQ = 30
INS_HNTCH_BW = 25
INS_HNTCH_ATT = 30
INS_HNTCH_REF = 0.071 (= 1/14)
INS_HNTCH_HMNCS = 7
but without any success.

There is very little documentation on CAN ESCs + dynamic notch. The only hints that this feature exists I could find are

  1. @andyp1per s comment ESC RPM check not allowing takeoff - #3 by andyp1per and
  2. a note “e) Harmonic notch support for CAN ESCs (KDECAN, PiccoloCAN, ToshibaCAN, UAVCAN)” in Copter 4.1.0-beta2 19-May-2021 in ardupilot/ArduCopter/ReleaseNotes.txt at master · ArduPilot/ardupilot · GitHub
  3. @tridge s Hobbywing DroneCAN ESC video and his remarks here https://youtu.be/2fQBczEFnO8?si=nXv0oz4HVD--Mw-E

Any advice? Is this a fault on the ESCs side (reporting eRPM instead of RPM), a CAN protocol issue (DroneCAN replaced UAVCAN in Copter 4.4.0). How could this be fixed (incl. code modifications if necessary)?

Any help would be very much appreciated, thanks in advance!

Do you know which CAN driver you are using for the ESCs? Usually you set ESC_NUM_POLES in periph or SERVO_BLH_POLES to get the correct RPM from eRPM. All ESCs report eRPM - it is the norm.

There is a scaling hack you can use with scripting, which I can tell you about if the POLES parameter does not exist for your ESCs.

The ESCs run UAVCAN (bldc/documentation/comm_can.md at master · vedderb/bldc · GitHub) and are connected to the CAN2 interface on the CubeOrange. In addition to the notch filter parameters mentioned above, in ArduPilot I set

CAN_P2_DRIVER = 2 (Second Driver)
CAN_D2_PROTOCOL = 1 (DroneCAN)
CAN_D2_UC_ESC_BM = 48 (…110000, Motor 5 and Motor 6)
I am able to control both ESCs/motors and get telemetry back from both.

Not sure I follow “Usually you set ESC_NUM_POLES in periph or SERVO_BLH_POLES to get the correct RPM from eRPM”. Where/how can I set ESC_NUM_POLES? The only parameters in Copter 4.3.0 related to number of poles I found are
CAN_D1_KDE_NPOLE (for KDE CAN ESCs only?)
SERVO_BLH_POLES (for BLHeli motors only?)

Ok, I understand what is going on now. The UAVCAN standard prescribes that the mechanical RPM is reported so VESC are violating the spec by reporting eRPM. There are a few ways out of this.

Fantastic, thanks a lot for your help!
I am, so I’ll give the lua script a shot, since I’m not familiar with the CAN & notch side of the ArduPilot stack. Will post the results here afterwards.

I briefly checked 7. List of standard data types - UAVCAN and uavcan.equipment.esc.Status should include a field “rpm”, but there is no definitive remark that these must be mechanical and not eletrical RPM.

Shouldn’t INS_HNTCH_REF = 1/(no of motor pole pairs) accomplish the same thing? The doc states
… The sensor data is converted to Hz automatically for use in the Harmonic Notch Filter. This reference value may also be used to scale the sensor data, if required. For example, rpm sensor data is required to measure heli motor RPM. Therefore the reference value can be used to scale the RPM sensor to the rotor RPM.

As mentoined above, I also tried INS_HNTCH_REF = 0.0714 = 1/14 but that did not change anything in the reported frequencies in the dataflash logfield FTN.NF1. Might be a bug (in 4.3.0), might be nothing.

The lua script worked as expected, thanks again for the help.

1 Like

Sounds like OskarF has resolved their issue. However, I just wanted to post about this should someone else stumble across this post in the future.

I have done a little digging in the VESC code and it looks as though VESC are adhering to the DroneCAN standard. This is where the RPM is packaged up to send via CAN telem:

It looks as though the eRPM is divided by the number of motor pole pairs before transmitting.

I have not had chance to test this out on the bench yet though. @OskarF did you try changing the number of poles in the VESC tool?

2 Likes

Interesting, will check the VESC config as soon as I have the chance but it’d sunrise me if the no of poles is set incorrectly. I am running VESC firmware 5.3 which is not the latest version.

Okay I found the issue: VESC firmware version 5.03 sends eRPM
In VESC v 5.03: bldc/libcanard/canard_driver.c at 0b5c9fd0ddefc89ae70ce792baeed303a1f8691b · vedderb/bldc · GitHub
Fix introduced with v 6.00
Send RPM instead of ERPM on UAVCAN · vedderb/bldc@0ee01ef · GitHub

Brief summary for those who stuble upon this or have simmilar issues:

  • VESC firmware <= 5.03 transmits eRPM instead if mechanical RPM
  • VESC firmware => 6.00 complies with the UAVCAN (DroneCAN) standard (sends mech. RPM)
  • if you have to use VESC FW <= v 5.03 for whatever reason or run a geared set-up use the lua script provided above to scale the reported RPM values (any scaling factor can be applied e.g. gear ratio, number of poles, …).
  • Dynamic notch based on CAN ESC telemetry is not very well documented, but works fine.
3 Likes