Skip to content

Commit a6c9c65

Browse files
committed
update linux build
1 parent 856ea26 commit a6c9c65

File tree

4 files changed

+15
-20
lines changed

4 files changed

+15
-20
lines changed

MavLinkCom/src/impl/AdHocConnectionImpl.cpp

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -25,9 +25,8 @@ AdHocConnectionImpl::~AdHocConnectionImpl() {
2525
close();
2626
}
2727

28-
template <typename PortType>
2928
std::shared_ptr<AdHocConnection> AdHocConnectionImpl::createConnection(const std::string &nodeName,
30-
std::shared_ptr<PortType> port) {
29+
std::shared_ptr<Port> port) {
3130
// std::shared_ptr<MavLinkCom> owner, const std::string& nodeName
3231
std::shared_ptr<AdHocConnection> con = std::make_shared<AdHocConnection>();
3332
con->startListening(nodeName, port);
@@ -38,7 +37,7 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectLocalUdp(const std:
3837
std::string localAddr, int localPort) {
3938
std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
4039
socket->connect(localAddr, localPort, "", 0);
41-
return createConnection<UdpClientPort>(nodeName, socket);
40+
return createConnection(nodeName, socket);
4241
}
4342

4443
std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectRemoteUdp(const std::string &nodeName,
@@ -52,7 +51,7 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectRemoteUdp(const std
5251

5352
std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
5453
socket->connect(local, 0, remoteAddr, remotePort);
55-
return createConnection<UdpClientPort>(nodeName, socket);
54+
return createConnection(nodeName, socket);
5655
}
5756

5857
std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectTcp(const std::string &nodeName, std::string localAddr,
@@ -65,7 +64,7 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectTcp(const std::stri
6564

6665
std::shared_ptr<TcpClientPort> socket = std::make_shared<TcpClientPort>();
6766
socket->connect(local, 0, remoteIpAddr, remotePort);
68-
return createConnection<TcpClientPort>(nodeName, socket);
67+
return createConnection(nodeName, socket);
6968
}
7069

7170
std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectSerial(const std::string &nodeName, std::string name,
@@ -81,7 +80,7 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectSerial(const std::s
8180
serial->write(reinterpret_cast<const uint8_t *>(initString.c_str()), static_cast<int>(initString.size()));
8281
}
8382

84-
return createConnection<SerialPort>(nodeName, serial);
83+
return createConnection(nodeName, serial);
8584
}
8685

8786
void AdHocConnectionImpl::startListening(std::shared_ptr<AdHocConnection> parent, const std::string &nodeName,

MavLinkCom/src/impl/AdHocConnectionImpl.hpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -53,9 +53,7 @@ class AdHocConnectionImpl {
5353
void unsubscribe(int id);
5454

5555
private:
56-
template <typename PortType>
57-
static std::shared_ptr<AdHocConnection> createConnection(const std::string &nodeName,
58-
std::shared_ptr<PortType> port);
56+
static std::shared_ptr<AdHocConnection> createConnection(const std::string &nodeName, std::shared_ptr<Port> port);
5957
void publishPackets();
6058
void readPackets();
6159
void drainQueue();

MavLinkCom/src/impl/MavLinkConnectionImpl.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,8 @@ MavLinkConnectionImpl::~MavLinkConnectionImpl() {
3434
close();
3535
}
3636

37-
template <typename PortType>
3837
std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::createConnection(const std::string &nodeName,
39-
std::shared_ptr<PortType> port) {
38+
std::shared_ptr<Port> port) {
4039
// std::shared_ptr<MavLinkCom> owner, const std::string& nodeName
4140
std::shared_ptr<MavLinkConnection> con = std::make_shared<MavLinkConnection>();
4241
con->startListening(nodeName, port);
@@ -47,7 +46,7 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectLocalUdp(const
4746
const std::string &localAddr, int localPort) {
4847
std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
4948
socket->connect(localAddr, localPort, "", 0);
50-
return createConnection<UdpClientPort>(nodeName, socket);
49+
return createConnection(nodeName, socket);
5150
}
5251

5352
std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectRemoteUdp(const std::string &nodeName,
@@ -61,7 +60,7 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectRemoteUdp(const
6160
}
6261
std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
6362
socket->connect(local, 0, remoteAddr, remotePort);
64-
return createConnection<UdpClientPort>(nodeName, socket);
63+
return createConnection(nodeName, socket);
6564
}
6665

6766
std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectTcp(const std::string &nodeName,
@@ -74,7 +73,7 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectTcp(const std::
7473
}
7574
std::shared_ptr<TcpClientPort> socket = std::make_shared<TcpClientPort>();
7675
socket->connect(local, 0, remoteIpAddr, remotePort);
77-
return createConnection<TcpClientPort>(nodeName, socket);
76+
return createConnection(nodeName, socket);
7877
}
7978

8079
std::string MavLinkConnectionImpl::acceptTcp(std::shared_ptr<MavLinkConnection> parent, const std::string &nodeName,
@@ -109,7 +108,7 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectSerial(const st
109108
serial->write(reinterpret_cast<const uint8_t *>(initString.c_str()), static_cast<int>(initString.size()));
110109
}
111110

112-
return createConnection<SerialPort>(nodeName, serial);
111+
return createConnection(nodeName, serial);
113112
}
114113

115114
void MavLinkConnectionImpl::startListening(std::shared_ptr<MavLinkConnection> parent, const std::string &nodeName,
@@ -144,7 +143,6 @@ void MavLinkConnectionImpl::close() {
144143
port->close();
145144
port = nullptr;
146145
}
147-
148146
if (read_thread.joinable()) {
149147
read_thread.join();
150148
}
@@ -159,6 +157,7 @@ void MavLinkConnectionImpl::close() {
159157
bool MavLinkConnectionImpl::isOpen() { return !closed; }
160158

161159
int MavLinkConnectionImpl::getTargetComponentId() { return this->other_component_id; }
160+
162161
int MavLinkConnectionImpl::getTargetSystemId() { return this->other_system_id; }
163162

164163
uint8_t MavLinkConnectionImpl::getNextSequence() {
@@ -169,8 +168,9 @@ uint8_t MavLinkConnectionImpl::getNextSequence() {
169168
void MavLinkConnectionImpl::ignoreMessage(uint8_t message_id) { ignored_messageids.insert(message_id); }
170169

171170
void MavLinkConnectionImpl::sendMessage(const MavLinkMessage &m) {
172-
if (ignored_messageids.find(m.msgid) != ignored_messageids.end())
171+
if (ignored_messageids.find(m.msgid) != ignored_messageids.end()) {
173172
return;
173+
}
174174

175175
if (closed) {
176176
return;

MavLinkCom/src/impl/MavLinkConnectionImpl.hpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -67,9 +67,7 @@ class MavLinkConnectionImpl {
6767
bool isPublishThread() const;
6868

6969
private:
70-
template <typename PortType>
71-
static std::shared_ptr<MavLinkConnection> createConnection(const std::string &nodeName,
72-
std::shared_ptr<PortType> port);
70+
static std::shared_ptr<MavLinkConnection> createConnection(const std::string &nodeName, std::shared_ptr<Port> port);
7371
void joinLeftSubscriber(std::shared_ptr<MavLinkConnection> remote, std::shared_ptr<MavLinkConnection> con,
7472
const MavLinkMessage &msg);
7573
void joinRightSubscriber(std::shared_ptr<MavLinkConnection> con, const MavLinkMessage &msg);

0 commit comments

Comments
 (0)