From 2bc1d4a5aed669309d67e4512ece32a33c3db668 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Mon, 17 Sep 2012 14:44:27 +1000
Subject: [PATCH] SITL: prevent a fd leak in GPS code

---
 libraries/Desktop/support/sitl_gps.cpp | 10 +++++++---
 1 file changed, 7 insertions(+), 3 deletions(-)

diff --git a/libraries/Desktop/support/sitl_gps.cpp b/libraries/Desktop/support/sitl_gps.cpp
index 277ce95a5..223cd1202 100644
--- a/libraries/Desktop/support/sitl_gps.cpp
+++ b/libraries/Desktop/support/sitl_gps.cpp
@@ -37,7 +37,7 @@ static uint8_t gps_delay;
 // state of GPS emulation
 static struct {
 	/* pipe emulating UBLOX GPS serial stream */
-	int gps_fd;
+	int gps_fd, client_fd;
 	uint32_t last_update; // milliseconds
 } gps_state;
 
@@ -55,12 +55,16 @@ ssize_t sitl_gps_read(int fd, void *buf, size_t count)
 int sitl_gps_pipe(void)
 {
 	int fd[2];
+	if (gps_state.client_fd != 0) {
+		return gps_state.client_fd;
+	}
 	pipe(fd);
-	gps_state.gps_fd = fd[1];
+	gps_state.gps_fd    = fd[1];
+	gps_state.client_fd = fd[0];
 	gps_state.last_update = millis();
 	set_nonblocking(gps_state.gps_fd);
 	set_nonblocking(fd[0]);
-	return fd[0];
+	return gps_state.client_fd;
 }
 
 
-- 
GitLab