From 23653f9f399ab13230945fc82512734e399de714 Mon Sep 17 00:00:00 2001
From: Julian Oes <julian@oes.ch>
Date: Tue, 1 Jan 2019 19:59:04 +0100
Subject: [PATCH] lockstep_scheduler: fix return value, remove errno

The API of cond_timedwait was wrong. It used return -1 and set errno
instead of returning the error as specified for pthread_cond_timedwait
which it tries to mock.
---
 .../src/lockstep_scheduler/src/lockstep_scheduler.cpp    | 9 +++------
 .../test/src/lockstep_scheduler_test.cpp                 | 5 ++---
 2 files changed, 5 insertions(+), 9 deletions(-)

diff --git a/platforms/posix/src/lockstep_scheduler/src/lockstep_scheduler.cpp b/platforms/posix/src/lockstep_scheduler/src/lockstep_scheduler.cpp
index 3080a7127b..14afbed9f0 100644
--- a/platforms/posix/src/lockstep_scheduler/src/lockstep_scheduler.cpp
+++ b/platforms/posix/src/lockstep_scheduler/src/lockstep_scheduler.cpp
@@ -57,8 +57,7 @@ int LockstepScheduler::cond_timedwait(pthread_cond_t *cond, pthread_mutex_t *loc
 
 		// The time has already passed.
 		if (time_us <= time_us_) {
-			errno = ETIMEDOUT;
-			return -1;
+			return ETIMEDOUT;
 		}
 
 		new_timed_wait = std::make_shared<TimedWait>();
@@ -80,8 +79,7 @@ int LockstepScheduler::cond_timedwait(pthread_cond_t *cond, pthread_mutex_t *loc
 			std::lock_guard<std::mutex> lock_timed_waits(timed_waits_mutex_);
 
 			if (result == 0 && new_timed_wait->timeout) {
-				errno = ETIMEDOUT;
-				result = -1;
+				result = ETIMEDOUT;
 			}
 
 			new_timed_wait->done = true;
@@ -104,9 +102,8 @@ int LockstepScheduler::usleep_until(uint64_t time_us)
 
 	int result = cond_timedwait(&cond, &lock, time_us);
 
-	if (result == -1 && errno == ETIMEDOUT) {
+	if (result == ETIMEDOUT) {
 		// This is expected because we never notified to the condition.
-		errno = 0;
 		result = 0;
 	}
 
diff --git a/platforms/posix/src/lockstep_scheduler/test/src/lockstep_scheduler_test.cpp b/platforms/posix/src/lockstep_scheduler/test/src/lockstep_scheduler_test.cpp
index 001590e1d6..f06edcbb15 100644
--- a/platforms/posix/src/lockstep_scheduler/test/src/lockstep_scheduler_test.cpp
+++ b/platforms/posix/src/lockstep_scheduler/test/src/lockstep_scheduler_test.cpp
@@ -34,8 +34,7 @@ void test_condition_timing_out()
 	// Use a thread to wait for condition while we already have the lock.
 	// This ensures the synchronization happens in the right order.
 	std::thread thread([&ls, &cond, &lock, &should_have_timed_out]() {
-		assert(ls.cond_timedwait(&cond, &lock, some_time_us + 1000) == -1);
-		assert(errno == ETIMEDOUT);
+		assert(ls.cond_timedwait(&cond, &lock, some_time_us + 1000) == ETIMEDOUT);
 		assert(should_have_timed_out);
 		// It should be re-locked afterwards, so we should be able to unlock it.
 		assert(pthread_mutex_unlock(&lock) == 0);
@@ -139,7 +138,7 @@ public:
 		else if (timeout_reached) {
 			is_done_ = true;
 			thread_->join();
-			assert(result_ == -1);
+			assert(result_ == ETIMEDOUT);
 		}
 	}
 private:
-- 
GitLab