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
`__main_thread_stack_base__` and `__main_thread_stack_end__` are
variables whose address is defined to be the corresponding part of the
stack. These are declared as `extern stkalign_t` in ChibiOS code, and
being declared as `extern uint32_t` in ArduPilot code creates a warning
at link time when using LTO. Correct the declaration to eliminate this
warning.
Also update `__main_stack_base__` and `__main_stack_end__` which don't
currently trigger this warning but serve similar purposes and so might
in the future.
The hardware expects an alignment of `stkalign_t` (which is 8 bytes) and
the linker script defines the variable values with this alignment as
well, so this is safe.
No code size or functional change.
this isn't built on the firmware server, so we won't notice when it dies
In this case the SMBUS batter define was being set differently
Also remove some redundant defines which come from includes anyway