Issue while Transmission of Mavlink Message on Telem2

Hi Team,

We are facing an issue in the transmission of a custom mavlink message from Telem2 Port.
Following is a detailed description and settings for our issue:

Issue: Mavlink messages loss on UART ports

Brief

We are witnessing a loss in the transmission of a mavlink commands from ArduCopter to Peripheral device. Peripheral device is connected to Telem2 Port. We are using Copter406 release based firmware. This issue is very persistent when all the UART ports are active for data communications. If we use only Telem 1 port for Herelink and Telem 2 port for peripheral device, mavlink command loss is not observed in flight tests.

Observations

Scenario 1

Mavlink COMMAND_LONG message sent on Telem2 port is missed very frequently. We have verified this by logging the mavlink messages on peripheral device. Message loss is very consistent but very random, in flight tests it occurs at a frequency of 50-75 percent.

Scenario 2

In some cases, COMMAND_LONG message is received to the peripheral device but after a significant delay of 8-10 seconds. Occasionally, this delay is even more than 10 seconds.

Analysis

In UARTDriver.cpp file, function UARTDriver::write_pending_bytes_DMA, it contains a check of if (dma_handle->has_contention()). If check is true, it is reducing the number of bytes to be written on the Serial Port.

Could this cause of the issue we are facing? If yes, then is there any specific reason why it has been implemented in such a manner?

If we fix the code for our needs, is there anything that we should consider from the UART hardware point of view.

Params Settings

Serial Options and Baudrate

SERIAL4_BAUD 57
SERIAL4_OPTIONS 0
SERIAL4_PROTOCOL 1
SERIAL3_BAUD 57
SERIAL3_OPTIONS 0
SERIAL3_PROTOCOL 1
SERIAL2_BAUD 57
SERIAL2_OPTIONS 0
SERIAL2_PROTOCOL 1
SERIAL1_BAUD 57
SERIAL1_OPTIONS 0
SERIAL1_PROTOCOL 1

SR parameters settings

SR1_RAW_SENS 2
SR1_EXT_STAT 2
SR1_RC_CHAN 2
SR1_POSITION 3
SR1_EXTRA1 10
SR1_EXTRA2 10
SR1_EXTRA3 3
SR1_PARAMS 0
SR2_RAW_SENS 0
SR2_EXT_STAT 0
SR2_RC_CHAN 0
SR2_POSITION 0
SR2_EXTRA1 0
SR2_EXTRA2 0
SR2_EXTRA3 0
SR2_PARAMS 0
SR3_RAW_SENS 0
SR3_EXT_STAT 0
SR3_RC_CHAN 0
SR3_POSITION 0
SR3_EXTRA1 0
SR3_EXTRA2 0
SR3_EXTRA3 0
SR3_PARAMS 0

Additional info

  1. We are transmitting HOME_POSITION and GLOBAL+POSITION_INT at a frequency of 1Hz on Serial4, i.e GPS2 Port.
  2. We are transmitting a custom 22 bytes message at a frequency of 95Hz at Serial3 Port, i.e GPS1 Port.

Any Help is appreciated

Before investigating any further, update to 4.1 and try again. There are number of fixes in this area in 4.1, most notably the use of shared DMA for UART’s.