Skip to content

Commit

Permalink
Rename MavLinkSemaphore to just Semaphore and add Apple OSX implement…
Browse files Browse the repository at this point in the history
…aiton.
  • Loading branch information
lovettchris committed Mar 7, 2017
1 parent a34d47c commit 878b70f
Show file tree
Hide file tree
Showing 11 changed files with 308 additions and 279 deletions.
4 changes: 2 additions & 2 deletions MavLinkCom/MavLinkCom.vcxproj
Original file line number Diff line number Diff line change
Expand Up @@ -241,7 +241,7 @@
<ClCompile Include="src\MavLinkMessageBase.cpp" />
<ClCompile Include="src\MavLinkMessages.cpp" />
<ClCompile Include="src\MavLinkNode.cpp" />
<ClCompile Include="src\MavLinkSemaphore.cpp" />
<ClCompile Include="src\Semaphore.cpp" />
<ClCompile Include="src\MavLinkTcpServer.cpp" />
<ClCompile Include="src\MavLinkVehicle.cpp" />
<ClCompile Include="src\impl\MavLinkVehicleImpl.cpp" />
Expand All @@ -267,6 +267,7 @@
<ClInclude Include="common_utils\sincos.hpp" />
<ClInclude Include="common_utils\type_utils.hpp" />
<ClInclude Include="common_utils\Utils.hpp" />
<ClInclude Include="include\Semaphore.hpp" />
<ClInclude Include="src\impl\MavLinkFtpClientImpl.hpp" />
<ClInclude Include="src\impl\MavLinkNodeImpl.hpp" />
<ClInclude Include="src\impl\MavLinkTcpServerImpl.hpp" />
Expand All @@ -275,7 +276,6 @@
<ClInclude Include="include\MavLinkMessageBase.hpp" />
<ClInclude Include="include\MavLinkMessages.hpp" />
<ClInclude Include="include\MavLinkNode.hpp" />
<ClInclude Include="include\MavLinkSemaphore.hpp" />
<ClInclude Include="include\MavLinkTcpServer.hpp" />
<ClInclude Include="include\MavLinkVehicle.hpp" />
<ClInclude Include="src\impl\MavLinkVehicleImpl.hpp" />
Expand Down
12 changes: 6 additions & 6 deletions MavLinkCom/MavLinkCom.vcxproj.filters
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,6 @@
<ClCompile Include="src\MavLinkNode.cpp">
<Filter>src</Filter>
</ClCompile>
<ClCompile Include="src\MavLinkSemaphore.cpp">
<Filter>src</Filter>
</ClCompile>
<ClCompile Include="src\MavLinkTcpServer.cpp">
<Filter>src</Filter>
</ClCompile>
Expand All @@ -73,6 +70,9 @@
<ClCompile Include="common_utils\Utils.cpp">
<Filter>common_utils</Filter>
</ClCompile>
<ClCompile Include="src\Semaphore.cpp">
<Filter>src</Filter>
</ClCompile>
</ItemGroup>
<ItemGroup>
<ClInclude Include="mavlink\checksum.h">
Expand Down Expand Up @@ -147,9 +147,6 @@
<ClInclude Include="include\MavLinkNode.hpp">
<Filter>include</Filter>
</ClInclude>
<ClInclude Include="include\MavLinkSemaphore.hpp">
<Filter>include</Filter>
</ClInclude>
<ClInclude Include="include\MavLinkTcpServer.hpp">
<Filter>include</Filter>
</ClInclude>
Expand Down Expand Up @@ -204,6 +201,9 @@
<ClInclude Include="src\serial_com\SocketInit.hpp">
<Filter>serial_com</Filter>
</ClInclude>
<ClInclude Include="include\Semaphore.hpp">
<Filter>include</Filter>
</ClInclude>
</ItemGroup>
<ItemGroup>
<Filter Include="Mavlink">
Expand Down
8 changes: 4 additions & 4 deletions MavLinkCom/MavLinkTest/UnitTests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
#include "MavLinkVideoStream.hpp"
#include "MavLinkTcpServer.hpp"
#include "MavLinkFtpClient.hpp"
#include "MavLinkSemaphore.hpp"
#include "Semaphore.hpp"
#include <iostream>

using namespace mavlink_utils;
Expand Down Expand Up @@ -51,7 +51,7 @@ void UnitTests::UdpPingTest() {

auto localConnection = MavLinkConnection::connectLocalUdp("jMavSim", "127.0.0.1", 14588);

MavLinkSemaphore received;
Semaphore received;
auto id = localConnection->subscribe([&](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg) {
printf(" Received message %d\n", msg.msgid);
received.post();
Expand Down Expand Up @@ -105,7 +105,7 @@ void UnitTests::TcpPingTest() {
return 0;
});

MavLinkSemaphore received;
Semaphore received;
auto client = MavLinkConnection::connectTcp("local", "127.0.0.1", "127.0.0.1", testPort);
client->subscribe([&](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg) {
printf("Received msg %d\n", msg.msgid);
Expand All @@ -124,7 +124,7 @@ void UnitTests::SerialPx4Test()
auto connection = MavLinkConnection::connectSerial("px4", com_port_, baud_rate_);

int count = 0;
MavLinkSemaphore received;
Semaphore received;

auto id = connection->subscribe([&](std::shared_ptr<MavLinkConnection> con, const MavLinkMessage& msg) {
//printf(" Received message %d\n", static_cast<int>(msg.msgid));
Expand Down
4 changes: 2 additions & 2 deletions MavLinkCom/include/AsyncResult.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#include <memory>
#include <string>
#include <future>
#include "MavLinkSemaphore.hpp"
#include "Semaphore.hpp"

namespace mavlinkcom {

Expand All @@ -18,7 +18,7 @@ namespace mavlinkcom {
{
public:
typedef std::function<void(int state)> CompletionHandler;
MavLinkSemaphore resultReceived_;
mavlink_utils::Semaphore resultReceived_;
T result_;
CompletionHandler owner_;
int state_ = 0;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,46 +1,43 @@
// Copyright (c) Microsoft Corporation. All rights reserved.
// Licensed under the MIT License.

#ifndef MavLinkCom_Semaphore_hpp
#define MavLinkCom_Semaphore_hpp
#include <memory>

#ifdef __APPLE__
#include <semaphore.h>
#endif

namespace mavlinkcom
{
/*
A semaphore is used to signal an event across threads. One thread blocks on Wait() until
the other thread calls Signal. It is a counting semaphore so if the thread calls Signal
before the Wait() then the Wait() does not block.
*/
class MavLinkSemaphore
{
public:
MavLinkSemaphore();
~MavLinkSemaphore();

// Increment the semaphore count to unblock the next waiter (the next wait caller will return).
// Throws exception if an error occurs.
void post();

// wait indefinitely for one call to post. If post has already been called then wait returns immediately
// decrementing the count so the next wait in the queue will block. Throws exception if an error occurs.
void wait();

// wait for a given number of milliseconds for one call to post. Returns false if a timeout or EINTR occurs.
// If post has already been called then timed_wait returns immediately decrementing the count so the next
// wait will block. Throws exception if an error occurs.
bool timed_wait(int milliseconds);
private:
class semaphore_impl;
std::unique_ptr<semaphore_impl> impl_;
};
}

#endif
#ifdef __APPLE__
int sem_timedwait(sem_t *sem, const struct timespec *abs_timeout);
#endif
// Copyright (c) Microsoft Corporation. All rights reserved.
// Licensed under the MIT License.

#ifndef common_utils_Semaphore_hpp
#define common_utils_Semaphore_hpp
#include <memory>

#ifdef __APPLE__
#include <semaphore.h>
#endif

namespace mavlink_utils
{
/*
A semaphore is used to signal an event across threads. One thread blocks on Wait() until
the other thread calls Signal. It is a counting semaphore so if the thread calls Signal
before the Wait() then the Wait() does not block.
*/
class Semaphore
{
public:
Semaphore();
~Semaphore();

// Increment the semaphore count to unblock the next waiter (the next wait caller will return).
// Throws exception if an error occurs.
void post();

// wait indefinitely for one call to post. If post has already been called then wait returns immediately
// decrementing the count so the next wait in the queue will block. Throws exception if an error occurs.
void wait();

// wait for a given number of milliseconds for one call to post. Returns false if a timeout or EINTR occurs.
// If post has already been called then timed_wait returns immediately decrementing the count so the next
// wait will block. Throws exception if an error occurs.
bool timed_wait(int milliseconds);
private:
class semaphore_impl;
std::unique_ptr<semaphore_impl> impl_;
};
}

#endif
Loading

0 comments on commit 878b70f

Please sign in to comment.