Plane 4.0 UAVCAN output rate inconsistency

Hello, I am having issues due to an inconsistent UAVCAN ArrayCommand output rate. This is an issue for me because I have a downstream component that implements a timeout, used to trigger a failsafe if ArrayCommand messages from the autopilot are not received.

Firstly, I’d be grateful if someone could tell me whether what I am observing is a bug or indeed a feature. Is the highly variable message rate by design, for example to reduce CAN bus bandwidth? If it is a feature, then I haven’t seen mention of it in the release notes or documentation (please enlighten me if I’ve missed it). Plane 3.9.8 provides a very consistent output rate.

Goal state:
Consistent ArrayCommand output rate of ~50Hz (CAN_D1_UC_SRV_RT)

Configuration/steps to recreate:
Babel (UAVCAN GUI Tool)
CubeBlack
Ardupilot 4.0.0/4.0.2
CAN_D1_PROTOCOL=1
CAN_D1_UC_ESC_BM=0
CAN_D1_UC_NODE=1
CAN_D1_UC_SRV_BM=32767
CAN_D1_UC_SRV_RT=50
CAN_D2_PROTOCOL=0
CAN_P1_BITRATE=1000000
CAN_P1_DRIVER=1
CAN_P2_BITRATE=1000000
CAN_P2_DRIVER=1
CAN_SLCAN_CPORT=0
CAN_SLCAN_SERNUM=-1
CAN_SLCAN_TIMOUT=0
(Full parameter file attached)
Test.parm (29.4 KB)

What I think should happen:
ArrayCommand with 16 channels - 8 CAN frames per message @ 50Hz, I would expect 400fps
Plus NodeStatus, SafetyState etc. so the expected frame rate should be >400fps

What actually happens:

2

Actual frame rate is ~375Hz(±20Hz) and very inconsistent with a message rate of ~43Hz(±5Hz). Seems to be independent of flight mode and servo activity, so if it is a feature and for efficiency reasons then it doesn’t appear to work particularly well. The most concerning aspect are occasional (every 5~10s) large gaps between messages (>200ms), which corresponds to 10 consecutive not sent messages @ 50Hz. I am confident that there is no frame corruption/loss occurring, rather Ardupilot is not sending the data. I have also tried different output rates, and the actual message rate is 10~15% lower than configured in all cases.

Any support would be greatly appreciated.

Many thanks, Tom.

@tridge or @bugobliterator are most familiar with the uavcan implementation.
Hopefully one of them can help.
Sorry for not seeing this earlier.

I notice your parameter file has CAN_D1_UC_SRV_BM=32767 which is 0x7FFF, which means 15 channels, not 16.
Even so, we should expect 50 messages per second, each containing one fully populated 8 frame ArrayCommand, so 400 frames per second.
What flight control board are you using?
Also, I have found in the past that the uavcan-gui-tool with a SLCAN adapter often can’t keep up with a high message rate.
As an alternative for more reliable message rate measurement I wrote this:
https://github.com/ardupilot/ardupilot/blob/master/libraries/AP_UAVCAN/examples/UAVCAN_sniffer
you put that on another flight controller on the same bus and it will report actual message rates.

Another thing you should try it raising SCHED_LOOP_RATE and see if that makes a difference

Hey Tridge, thanks for getting back to me - responses in order below:

Yes you’re quite right, I was testing multiple configurations and had the CAN_D1_UC_SRV_BM mixed up in the parameter file I uploaded.

For this example I was using a CubeBlack on the standard dock. I’ve been able to replicate the results with an OG Pixhawk (FMUv2) though.

So I first noticed the “issue” using a downstream component that I have developed that uses an STM32F407, running ChibiOS and libcanard and got exactly the same results. So I suspect that the Babel+UAVCAN GUI Tool combo is indeed accurate.

I’ll give that a go, thanks.

I’ve tried varying the SCHED_LOOP_RATE up to ~300Hz, and the UAVCAN message rate stays at ~80% of the CAN_D1_UC_SRV_RT regardless.

Are many people actually using the ArrayCommand output? The ESC RawCommand seems to work perfectly (I suspect that’s much more commonly used).

Tom.