the timing table was not correct, thanks to APD for pointing this out.
This is recalculated from
https://www.kvaser.com/support/calculators/can-fd-bit-timing-calculator,
with transmitter timing delay compensation added and tested with Salae
captures to ensure we are getting the right bit rates
our CANFD timings were resulting in a lot of busoff errors. Here is an
example of master at 1Mbit/5MBit:
Getting @SYS/can0_stats.txt as -
------- Clock Config -------
CAN_CLK_FREQ: 80MHz
Std Timings: bitrate=1000000 presc=7
sjw=0 bs1=7 bs2=0 sample_point=90.00000%
FD Timings: bitrate=5000000 presc=1
sjw=0 bs1=5 bs2=0 sample_point=90.00000%
------- CAN Interface Stats -------
tx_requests: 2689
tx_rejected: 0
tx_overflow: 443
tx_success: 7
tx_timedout: 2232
tx_abort: 0
rx_received: 18470
rx_overflow: 0
rx_errors: 0
num_busoff_err: 34439
num_events: 18477
ECR: F8
fdf_rx: 18467
fdf_tx_req: 2182
fdf_tx: 0
here is an example with the new timings:
------- Clock Config -------
CAN_CLK_FREQ: 80MHz
Std Timings: bitrate=1000000 presc=8
sjw=1 bs1=8 bs2=1 sample_point=90.00000%
FD Timings: bitrate=8000000 presc=2
sjw=3 bs1=8 bs2=3 sample_point=80.00000%
------- CAN Interface Stats -------
tx_requests: 3023
tx_rejected: 0
tx_overflow: 0
tx_success: 3023
tx_timedout: 0
tx_abort: 0
rx_received: 27865
rx_overflow: 0
rx_errors: 0
num_busoff_err: 0
num_events: 30888
ECR: 0
fdf_rx: 27862
fdf_tx_req: 3016
fdf_tx: 3016
I am testing between a CubeOrange and a Pixhawk6X. I tested 1, 2, 4, 5
and 8 MBit (which are the only valid FD bitrates in our parameters)
Many thanks to Kai from Salient Motion for finding this issue and
providing the corrected timing table
this saves flash space and makes CAN forwarding for any bus without
reconfigure/reboot easy. CAN filtering is not useful in the main
flight controller firmware as we want to see nearly all packets
these wait busy loops can take a very long time, and end up causing
interrupts to be lost elsewhere in the system, causing lost bytes on
UARTs
We should not have while loops waiting on peripharals like this. If we
do need to wait for a flag to clear then it needs to be done in a low
priority thread, or we need to check for completion in a timer
CAN still seems to work with this change, but needs flight testing