From 74990cadc8fe61bf541c2ec6fa29db3b11dd1feb Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Beat=20K=C3=BCng?= <beat-kueng@gmx.net>
Date: Tue, 30 Apr 2019 15:25:44 +0200
Subject: [PATCH] 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.
---
 src/modules/uORB/uORBDeviceMaster.cpp | 46 +++++++++++++++++++++------
 src/modules/uORB/uORBDeviceMaster.hpp |  4 +--
 2 files changed, 38 insertions(+), 12 deletions(-)

diff --git a/src/modules/uORB/uORBDeviceMaster.cpp b/src/modules/uORB/uORBDeviceMaster.cpp
index 6bce477de6..6ccdc4d016 100644
--- a/src/modules/uORB/uORBDeviceMaster.cpp
+++ b/src/modules/uORB/uORBDeviceMaster.cpp
@@ -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) {
diff --git a/src/modules/uORB/uORBDeviceMaster.hpp b/src/modules/uORB/uORBDeviceMaster.hpp
index 242201f275..60c9c0d628 100644
--- a/src/modules/uORB/uORBDeviceMaster.hpp
+++ b/src/modules/uORB/uORBDeviceMaster.hpp
@@ -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;
 
-- 
GitLab