Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
65 changes: 35 additions & 30 deletions ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs
Original file line number Diff line number Diff line change
Expand Up @@ -5087,10 +5087,35 @@ public async Task<MAVLinkMessage> readPacketAsync()

// packet is now verified

// extract wp's/rally/fence/camera feedback/params from stream, including gcs packets on playback
// log before any processing that could send response packets (e.g. timesync)
try
{
SaveToTlog(new Span<byte>(buffer));

if (logfile != null)
{
lock (logfile)
Comment on lines +5090 to +5097
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

SaveToTlog() performs synchronous file I/O (and allocates via packet.ToArray() inside SaveToTlog) and is now executed while readlock is held. This extends the critical section that blocks other readPacketAsync() callers and can increase receive latency / risk backlog when logging to slow storage. Consider releasing readlock immediately after the packet is verified/resized, then perform tlog write + subsequent processing (including timesync/mission handling) outside the lock so reading can continue while logging/processing occurs.

Copilot uses AI. Check for mistakes.
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

comment on 4926 says Readlock ended here, but it is ended at 5216. Seems like a serious consideration, the exact ordering of logging/processing/packet sequence error check is beyond my scope. Maybe the solution would be to move processInfoFromStream (or parts of it) down, instead of moving SaveToTlog up

{
if (msgid == 0)
{
if (logfile != null && logfile.CanWrite)
logfile.Flush();
if (rawlogfile != null && rawlogfile.CanWrite)
rawlogfile.Flush();
}
}
}
}
catch (Exception ex)
{
log.Error(ex);
}

// extract wp's/rally/fence/camera feedback/params from stream, including gcs packets on playback.
// may also send responses (e.g. timesync reply)
if (buffer.Length >= 5)
{
getInfoFromStream(ref message, sysid, compid);
processInfoFromStream(ref message, sysid, compid);
}

// if its a gcs packet - dont process further
Expand Down Expand Up @@ -5335,31 +5360,6 @@ public async Task<MAVLinkMessage> readPacketAsync()
}
}

try
{
// this is to ensure the log is in packet order, as the events on Received may send a packet. (ie mavftp)
SaveToTlog(new Span<byte>(buffer));

if (logfile != null)
{
lock (logfile)
{
if (msgid == 0)
{
// flush on heartbeat - 1 seconds
if (logfile != null && logfile.CanWrite)
logfile.Flush();
if (rawlogfile != null && rawlogfile.CanWrite)
rawlogfile.Flush();
}
}
}
}
catch (Exception ex)
{
log.Error(ex);
}

// process for all mavs, filtering done inside - subscription handler
PacketReceived(message);

Expand Down Expand Up @@ -5611,10 +5611,15 @@ public void UnSubscribeToPacketType(int id)


/// <summary>
/// Used to extract mission from log file - both sent or received
/// Processes a MAVLink packet received from the stream and updates cached state for the
/// addressed vehicle/component. This includes tracking mission/fence/rally and parameter
/// data from sent or received traffic, and may also trigger protocol side effects such as
/// sending responses for messages that require them (for example, TIMESYNC handling).
/// </summary>
/// <param name="buffer">packet</param>
private void getInfoFromStream(ref MAVLinkMessage buffer, byte sysid, byte compid)
/// <param name="buffer">The MAVLink packet to process. Its contents may be used to update local mission/parameter state and may cause protocol responses to be sent.</param>
/// <param name="sysid">The system id associated with the packet when resolving vehicle state updates.</param>
/// <param name="compid">The component id associated with the packet when resolving vehicle state updates.</param>
private void processInfoFromStream(ref MAVLinkMessage buffer, byte sysid, byte compid)
{
if (buffer.msgid == (byte) MAVLINK_MSG_ID.MISSION_COUNT)
{
Expand Down