Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

libmavconn: fix deadlock when call close() #1679

Merged

Conversation

SylvainPastor
Copy link

@SylvainPastor SylvainPastor commented Dec 17, 2021

MavconnTCPClient: When calling the close() function (by a different thread), a mutex is taken at
the start of this function which closes the socket and waits the end of io_service thread.

Closing the socket causes the Operation aborted error in do_recv() function called by
io_service thread which in turn calls the close() function.

This causes a 'deadlock'.

fix: Reduce the scope of the mutex in the close() function so that it is released before
waiting the end of io_service thread.

  When calling the close() function (by a different thread), a lock (mutex) is taken at
  the start of this function which closes the socket and waits the end of io_service thread.

  Closing the socket causes the 'Operation aborted' error in do_recv() function called by
  io_service thread which in turn calls the close() function: sthis->close().

  This causes a 'deadlock'.

  fix: Reduce the scope of the lock in the close() function so that it is released before
  waiting for the thread to end.
@vooon vooon added this to the Version 1.13 milestone Dec 17, 2021
Copy link
Member

@vooon vooon left a comment

Choose a reason for hiding this comment

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

LGTM, Thanks!

@vooon vooon merged commit b9418a4 into mavlink:ros2 Dec 17, 2021
@vooon vooon modified the milestones: Version 1.13, Version 2.1 Dec 17, 2021
SylvainPastor pushed a commit to SylvainPastor/mavros that referenced this pull request Mar 3, 2022
Same problems as for the TCP:
  - mavlink#1682: fix std::system_error when tcp interface loses connection
  - mavlink#1679: fix deadlock when call close()
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants