From e0f08193659f1269ae00fb32d0d9ec56910b1b23 Mon Sep 17 00:00:00 2001
From: Esteve Fernandez <esteve@osrfoundation.org>
Date: Thu, 3 Dec 2015 16:30:34 -0800
Subject: [PATCH] Avoid unused return value warning

---
 rclcpp/src/rclcpp/utilities.cpp | 12 +++++++++++-
 1 file changed, 11 insertions(+), 1 deletion(-)

diff --git a/rclcpp/src/rclcpp/utilities.cpp b/rclcpp/src/rclcpp/utilities.cpp
index 4ae1b551b3..73c5794e38 100644
--- a/rclcpp/src/rclcpp/utilities.cpp
+++ b/rclcpp/src/rclcpp/utilities.cpp
@@ -117,7 +117,17 @@ rclcpp::utilities::init(int argc, char * argv[])
     // NOLINTNEXTLINE(runtime/arrays)
     char error_string[error_length];
 #ifndef _WIN32
-    strerror_r(errno, error_string, error_length);
+#if (_POSIX_C_SOURCE >= 200112L || _XOPEN_SOURCE >= 600) && ! _GNU_SOURCE
+    int error_status = strerror_r(errno, error_string, error_length);
+    if (error_status != 0) {
+      throw std::runtime_error("Failed to set error message");
+    }
+#else
+    char * msg = strerror_r(errno, error_string, error_length);
+    if (msg != error_string) {
+      strncpy(error_string, msg, sizeof(error_string));
+    }
+#endif
 #else
     strerror_s(error_string, error_length, errno);
 #endif