Skip to content
Snippets Groups Projects
Commit 74990cad authored by Beat Küng's avatar Beat Küng Committed by Julian Oes
Browse files

uorb: avoid printf while DeviceMaster is locked

This fixes a potential dead-lock when 'uorb status' was used via MAVLink
shell.
The dead-lock chain is: DeviceMaster::lock() -> printf -> output to a pipe,
which blocks until a reader reads the data. In that case it's mavlink.
If mavlink makes a call that requires DeviceMaster::lock() (such as
orb_exists), it dead-locks.

This patch moves all printf's out of the locked state.
parent 29719894
No related branches found
No related tags found
No related merge requests found
......@@ -161,22 +161,38 @@ void uORB::DeviceMaster::printStatistics(bool reset)
PX4_INFO("TOPIC, NR LOST MSGS");
bool had_print = false;
/* Add all nodes to a list while locked, and then print them in unlocked state, to avoid potential
* dead-locks (where printing blocks) */
lock();
DeviceNodeStatisticsData *first_node = nullptr;
DeviceNodeStatisticsData *cur_node = nullptr;
size_t max_topic_name_length = 0;
int num_topics = 0;
int ret = addNewDeviceNodes(&first_node, num_topics, max_topic_name_length, nullptr, 0);
unlock();
for (const auto &node : _node_list) {
if (node->print_statistics(reset)) {
if (ret != 0) {
PX4_ERR("addNewDeviceNodes failed (%i)", ret);
}
cur_node = first_node;
while (cur_node) {
if (cur_node->node->print_statistics(reset)) {
had_print = true;
}
}
unlock();
DeviceNodeStatisticsData *prev = cur_node;
cur_node = cur_node->next;
delete prev;
}
if (!had_print) {
PX4_INFO("No lost messages");
}
}
void uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node, int &num_topics,
int uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node, int &num_topics,
size_t &max_topic_name_length, char **topic_filter, int num_filters)
{
DeviceNodeStatisticsData *cur_node = nullptr;
......@@ -227,8 +243,7 @@ void uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node
}
if (!last_node) {
PX4_ERR("mem alloc failed");
break;
return -ENOMEM;
}
last_node->node = node;
......@@ -242,6 +257,8 @@ void uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node
last_node->last_lost_msg_count = last_node->node->lost_message_count();
last_node->last_pub_msg_count = last_node->node->published_message_count();
}
return 0;
}
#define CLEAR_LINE "\033[K"
......@@ -284,11 +301,15 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
DeviceNodeStatisticsData *cur_node = nullptr;
size_t max_topic_name_length = 0;
int num_topics = 0;
addNewDeviceNodes(&first_node, num_topics, max_topic_name_length, topic_filter, num_filters);
int ret = addNewDeviceNodes(&first_node, num_topics, max_topic_name_length, topic_filter, num_filters);
/* a DeviceNode is never deleted, so it's save to unlock here and still access the DeviceNodes */
unlock();
if (ret != 0) {
PX4_ERR("addNewDeviceNodes failed (%i)", ret);
}
#ifdef __PX4_QURT //QuRT has no poll()
only_once = true;
#else
......@@ -310,7 +331,7 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
for (int k = 0; k < 5; k++) {
char c;
int ret = ::poll(&fds, 1, 0); //just want to check if there is new data available
ret = ::poll(&fds, 1, 0); //just want to check if there is new data available
if (ret > 0) {
......@@ -365,8 +386,13 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
}
lock();
addNewDeviceNodes(&first_node, num_topics, max_topic_name_length, topic_filter, num_filters);
ret = addNewDeviceNodes(&first_node, num_topics, max_topic_name_length, topic_filter, num_filters);
unlock();
if (ret != 0) {
PX4_ERR("addNewDeviceNodes failed (%i)", ret);
}
}
if (only_once) {
......
......@@ -98,8 +98,8 @@ private:
DeviceNodeStatisticsData *next = nullptr;
};
void addNewDeviceNodes(DeviceNodeStatisticsData **first_node, int &num_topics, size_t &max_topic_name_length,
char **topic_filter, int num_filters);
int addNewDeviceNodes(DeviceNodeStatisticsData **first_node, int &num_topics, size_t &max_topic_name_length,
char **topic_filter, int num_filters);
friend class uORB::Manager;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment