Fix mavros_router segfault with mutex on remote_addrs#2138
Conversation
|
Thanks for tracking down this race — the segfault is real and the fix direction is right. I have an in-flight refactor of the same file in #2105 that restructures To keep both PRs mergeable with minimal rebase pain, could you make two changes? 1. Remove the lock in
|
|
Thank you for the feedback @vooon. I've updated the code accordingly. Were you able to reproduce the segfault? (Side note that I also did not have the lock inside |
| stat.addf("Remotes count", "%zu", this->remote_addrs.size()); | ||
| std::set<addr_t> remote_addrs_copy; | ||
| { | ||
| std::unique_lock<std::shared_mutex> lock(this->remote_addrs_mutex); |
There was a problem hiding this comment.
Maybe shared lock, since we're just reading here?
There was a problem hiding this comment.
In the mavros_router, I've encountered a segmentation fault because
this->remote_addrsis accessed by two threads concurrently without lock mechanism.Solution: protect concurrent calls with a mutex:
remote_addrs_mutex.To reproduce the segfault: change the frequency of the timer below from 60s to 1ms
this->create_wall_timer(60s, std::bind(&Router::periodic_clear_stale_remote_addrs, this));