diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp
index aadc006f42e62f2f3b47726967623719527c9046..6576c383379b99ff5ffa5d30ea68025ee484135a 100644
--- a/src/modules/simulator/simulator_mavlink.cpp
+++ b/src/modules/simulator/simulator_mavlink.cpp
@@ -679,8 +679,8 @@ void Simulator::pollForMAVLinkMessages(bool publish)
 
 		while (true) {
 			// Once we receive something, we're most probably good and can carry on.
-			int len = recvfrom(_fd, _buf, sizeof(_buf), 0,
-					   (struct sockaddr *)&_srcaddr, (socklen_t *)&_addrlen);
+			int len = ::recvfrom(_fd, _buf, sizeof(_buf), 0,
+					     (struct sockaddr *)&_srcaddr, (socklen_t *)&_addrlen);
 
 			if (len > 0) {
 				break;
@@ -716,7 +716,7 @@ void Simulator::pollForMAVLinkMessages(bool publish)
 				break;
 
 			} else {
-				close(_fd);
+				::close(_fd);
 				system_sleep(1);
 			}
 		}
@@ -798,8 +798,8 @@ void Simulator::pollForMAVLinkMessages(bool publish)
 
 		if (fds[0].revents & POLLIN) {
 
-			int len = recvfrom(_fd, _buf, sizeof(_buf), 0,
-					   (struct sockaddr *)&_srcaddr, (socklen_t *)&_addrlen);
+			int len = ::recvfrom(_fd, _buf, sizeof(_buf), 0,
+					     (struct sockaddr *)&_srcaddr, (socklen_t *)&_addrlen);
 
 			if (len > 0) {
 				mavlink_message_t msg;