Browse Source

mavlink: destroy all instances fix potential dead lock

master
Daniel Agar 3 years ago
parent
commit
8b1543e3b0
  1. 46
      src/modules/mavlink/mavlink_main.cpp

46
src/modules/mavlink/mavlink_main.cpp

@ -338,31 +338,46 @@ Mavlink::get_instance_for_network_port(unsigned long port) @@ -338,31 +338,46 @@ Mavlink::get_instance_for_network_port(unsigned long port)
int
Mavlink::destroy_all_instances()
{
LockGuard lg{mavlink_module_mutex};
PX4_INFO("waiting for instances to stop");
unsigned iterations = 0;
PX4_INFO("waiting for instances to stop");
while (iterations < 1000) {
int running = 0;
for (Mavlink *inst_to_del : mavlink_module_instances) {
if (inst_to_del != nullptr) {
/* set flag to stop thread and wait for all threads to finish */
inst_to_del->request_stop();
pthread_mutex_lock(&mavlink_module_mutex);
while (inst_to_del->running()) {
printf(".");
fflush(stdout);
px4_usleep(10000);
iterations++;
for (Mavlink *inst_to_del : mavlink_module_instances) {
if (inst_to_del != nullptr) {
if (inst_to_del->running()) {
running++;
if (iterations > 1000) {
PX4_ERR("Couldn't stop all mavlink instances.");
return PX4_ERROR;
// set flag to stop thread and wait for all threads to finish
inst_to_del->request_stop();
}
}
}
pthread_mutex_unlock(&mavlink_module_mutex);
if (running == 0) {
break;
} else if (iterations > 1000) {
PX4_ERR("Couldn't stop all mavlink instances.");
return PX4_ERROR;
} else {
iterations++;
printf(".");
fflush(stdout);
px4_usleep(10000);
}
}
//we know all threads have exited, so it's safe to delete objects.
LockGuard lg{mavlink_module_mutex};
// we know all threads have exited, so it's safe to delete objects.
for (Mavlink *inst_to_del : mavlink_module_instances) {
delete inst_to_del;
}
@ -370,7 +385,6 @@ Mavlink::destroy_all_instances() @@ -370,7 +385,6 @@ Mavlink::destroy_all_instances()
delete _event_buffer;
_event_buffer = nullptr;
printf("\n");
PX4_INFO("all instances stopped");
return OK;
}

Loading…
Cancel
Save