Skip to content

Commit

Permalink
Merge pull request #935 from mavlink/fix-segfault
Browse files Browse the repository at this point in the history
core: fix segfault on register_plugin
  • Loading branch information
julianoes authored Dec 18, 2019
2 parents 01e8148 + a36f2d0 commit d45d34a
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 21 deletions.
21 changes: 2 additions & 19 deletions src/core/system_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,6 @@ void SystemImpl::register_mavlink_message_handler(

MAVLinkHandlerTableEntry entry = {msg_id, callback, cookie};
_mavlink_handler_table.push_back(entry);
// Push back can move the std::vector and therefore invalidate the iterator.
_iterator_invalidated = true;
}

void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
Expand All @@ -97,7 +95,6 @@ void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void*
/* no ++it */) {
if (it->msg_id == msg_id && it->cookie == cookie) {
it = _mavlink_handler_table.erase(it);
_iterator_invalidated = true;
} else {
++it;
}
Expand All @@ -112,7 +109,6 @@ void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
/* no ++it */) {
if (it->cookie == cookie) {
it = _mavlink_handler_table.erase(it);
_iterator_invalidated = true;
} else {
++it;
}
Expand Down Expand Up @@ -147,33 +143,20 @@ void SystemImpl::process_mavlink_message(mavlink_message_t& message)
}
}

_mavlink_handler_table_mutex.lock();
std::lock_guard<std::mutex> lock(_mavlink_handler_table_mutex);

#if MESSAGE_DEBUGGING == 1
bool forwarded = false;
#endif
for (auto it = _mavlink_handler_table.begin(); it != _mavlink_handler_table.end(); /* ++it */) {
for (auto it = _mavlink_handler_table.begin(); it != _mavlink_handler_table.end(); ++it) {
if (it->msg_id == message.msgid) {
#if MESSAGE_DEBUGGING == 1
LogDebug() << "Forwarding msg " << int(message.msgid) << " to " << size_t(it->cookie);
forwarded = true;
#endif
_mavlink_handler_table_mutex.unlock();
it->callback(message);
_mavlink_handler_table_mutex.lock();
}

if (_iterator_invalidated) {
// Someone messed with the map while we were doing the callback.
// We need to start over. This means that we might call something twice but that's
// probably better than to drop the message.
it = _mavlink_handler_table.begin();
_iterator_invalidated = false;
} else {
++it;
}
}
_mavlink_handler_table_mutex.unlock();

#if MESSAGE_DEBUGGING == 1
if (!forwarded) {
Expand Down
2 changes: 0 additions & 2 deletions src/core/system_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -311,8 +311,6 @@ class SystemImpl {

ThreadPool _thread_pool{3};

bool _iterator_invalidated{false};

std::mutex _param_changed_callbacks_mutex{};
std::map<const void*, param_changed_callback_t> _param_changed_callbacks{};

Expand Down

0 comments on commit d45d34a

Please sign in to comment.