Skip to content

Commit

Permalink
update linux build
Browse files Browse the repository at this point in the history
  • Loading branch information
admercs committed Mar 3, 2024
1 parent 15db28d commit 856ea26
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 15 deletions.
21 changes: 7 additions & 14 deletions MavLinkCom/src/impl/MavLinkConnectionImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,9 @@ MavLinkConnectionImpl::~MavLinkConnectionImpl() {
close();
}

template <typename PortType>
std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::createConnection(const std::string &nodeName,
std::shared_ptr<Port> port) {
std::shared_ptr<PortType> port) {
// std::shared_ptr<MavLinkCom> owner, const std::string& nodeName
std::shared_ptr<MavLinkConnection> con = std::make_shared<MavLinkConnection>();
con->startListening(nodeName, port);
Expand All @@ -45,10 +46,8 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::createConnection(const
std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectLocalUdp(const std::string &nodeName,
const std::string &localAddr, int localPort) {
std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();

socket->connect(localAddr, localPort, "", 0);

return createConnection(nodeName, socket);
return createConnection<UdpClientPort>(nodeName, socket);
}

std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectRemoteUdp(const std::string &nodeName,
Expand All @@ -60,12 +59,9 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectRemoteUdp(const
if (remoteAddr == "127.0.0.1") {
local = "127.0.0.1";
}

std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();

socket->connect(local, 0, remoteAddr, remotePort);

return createConnection(nodeName, socket);
return createConnection<UdpClientPort>(nodeName, socket);
}

std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectTcp(const std::string &nodeName,
Expand All @@ -76,12 +72,9 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectTcp(const std::
if (remoteIpAddr == "127.0.0.1") {
local = "127.0.0.1";
}

std::shared_ptr<TcpClientPort> socket = std::make_shared<TcpClientPort>();

socket->connect(local, 0, remoteIpAddr, remotePort);

return createConnection(nodeName, socket);
return createConnection<TcpClientPort>(nodeName, socket);
}

std::string MavLinkConnectionImpl::acceptTcp(std::shared_ptr<MavLinkConnection> parent, const std::string &nodeName,
Expand All @@ -90,7 +83,7 @@ std::string MavLinkConnectionImpl::acceptTcp(std::shared_ptr<MavLinkConnection>
close();
std::shared_ptr<TcpClientPort> socket = std::make_shared<TcpClientPort>();

port = socket; // this is so that a call to close() can cancel this blocking accept call.
port = std::make_shared<Port>(*socket); // this is so that a call to close() can cancel this blocking accept call.
socket->accept(localAddr, listeningPort);

std::string remote = socket->remoteAddress();
Expand All @@ -116,7 +109,7 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectSerial(const st
serial->write(reinterpret_cast<const uint8_t *>(initString.c_str()), static_cast<int>(initString.size()));
}

return createConnection(nodeName, serial);
return createConnection<SerialPort>(nodeName, serial);
}

void MavLinkConnectionImpl::startListening(std::shared_ptr<MavLinkConnection> parent, const std::string &nodeName,
Expand Down
4 changes: 3 additions & 1 deletion MavLinkCom/src/impl/MavLinkConnectionImpl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,9 @@ class MavLinkConnectionImpl {
bool isPublishThread() const;

private:
static std::shared_ptr<MavLinkConnection> createConnection(const std::string &nodeName, std::shared_ptr<Port> port);
template <typename PortType>
static std::shared_ptr<MavLinkConnection> createConnection(const std::string &nodeName,
std::shared_ptr<PortType> port);
void joinLeftSubscriber(std::shared_ptr<MavLinkConnection> remote, std::shared_ptr<MavLinkConnection> con,
const MavLinkMessage &msg);
void joinRightSubscriber(std::shared_ptr<MavLinkConnection> con, const MavLinkMessage &msg);
Expand Down
2 changes: 2 additions & 0 deletions MavLinkCom/src/serial_com/TcpClientPort.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
#define SERIAL_COM_TCPCLIENTPORT_HPP

#include "Port.h"
#include <memory>
#include <string>

class TcpClientPort : public Port {
public:
Expand Down

0 comments on commit 856ea26

Please sign in to comment.