Skip to content

Commit 15db28d

Browse files
committed
update linux build
1 parent 22bb210 commit 15db28d

File tree

7 files changed

+24
-16
lines changed

7 files changed

+24
-16
lines changed

MavLinkCom/src/impl/AdHocConnectionImpl.cpp

Lines changed: 11 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -17,15 +17,17 @@ AdHocConnectionImpl::AdHocConnectionImpl() {
1717
::memset(&mavlink_intermediate_status_, 0, sizeof(mavlink_status_t));
1818
::memset(&mavlink_status_, 0, sizeof(mavlink_status_t));
1919
}
20+
2021
std::string AdHocConnectionImpl::getName() { return name; }
2122

2223
AdHocConnectionImpl::~AdHocConnectionImpl() {
2324
con_.reset();
2425
close();
2526
}
2627

28+
template <typename PortType>
2729
std::shared_ptr<AdHocConnection> AdHocConnectionImpl::createConnection(const std::string &nodeName,
28-
std::shared_ptr<Port> port) {
30+
std::shared_ptr<PortType> port) {
2931
// std::shared_ptr<MavLinkCom> owner, const std::string& nodeName
3032
std::shared_ptr<AdHocConnection> con = std::make_shared<AdHocConnection>();
3133
con->startListening(nodeName, port);
@@ -35,10 +37,8 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::createConnection(const std
3537
std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectLocalUdp(const std::string &nodeName,
3638
std::string localAddr, int localPort) {
3739
std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
38-
3940
socket->connect(localAddr, localPort, "", 0);
40-
41-
return createConnection(nodeName, socket);
41+
return createConnection<UdpClientPort>(nodeName, socket);
4242
}
4343

4444
std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectRemoteUdp(const std::string &nodeName,
@@ -51,10 +51,8 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectRemoteUdp(const std
5151
}
5252

5353
std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
54-
5554
socket->connect(local, 0, remoteAddr, remotePort);
56-
57-
return createConnection(nodeName, socket);
55+
return createConnection<UdpClientPort>(nodeName, socket);
5856
}
5957

6058
std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectTcp(const std::string &nodeName, std::string localAddr,
@@ -66,17 +64,15 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectTcp(const std::stri
6664
}
6765

6866
std::shared_ptr<TcpClientPort> socket = std::make_shared<TcpClientPort>();
69-
7067
socket->connect(local, 0, remoteIpAddr, remotePort);
71-
72-
return createConnection(nodeName, socket);
68+
return createConnection<TcpClientPort>(nodeName, socket);
7369
}
7470

7571
std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectSerial(const std::string &nodeName, std::string name,
7672
int baudRate, const std::string initString) {
7773
std::shared_ptr<SerialPort> serial = std::make_shared<SerialPort>();
78-
7974
int hr = serial->connect(name.c_str(), baudRate);
75+
8076
if (hr != 0)
8177
throw std::runtime_error(Utils::stringf("Could not open the serial port %s, error=%d", name.c_str(), hr));
8278

@@ -85,7 +81,7 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectSerial(const std::s
8581
serial->write(reinterpret_cast<const uint8_t *>(initString.c_str()), static_cast<int>(initString.size()));
8682
}
8783

88-
return createConnection(nodeName, serial);
84+
return createConnection<SerialPort>(nodeName, serial);
8985
}
9086

9187
void AdHocConnectionImpl::startListening(std::shared_ptr<AdHocConnection> parent, const std::string &nodeName,
@@ -121,6 +117,7 @@ void AdHocConnectionImpl::close() {
121117
bool AdHocConnectionImpl::isOpen() { return !closed; }
122118

123119
int AdHocConnectionImpl::getTargetComponentId() { return this->other_component_id; }
120+
124121
int AdHocConnectionImpl::getTargetSystemId() { return this->other_system_id; }
125122

126123
void AdHocConnectionImpl::sendMessage(const std::vector<uint8_t> &msg) {
@@ -143,6 +140,7 @@ int AdHocConnectionImpl::subscribe(AdHocMessageHandler handler) {
143140
snapshot_stale = true;
144141
return entry.id;
145142
}
143+
146144
void AdHocConnectionImpl::unsubscribe(int id) {
147145
std::lock_guard<std::mutex> guard(listener_mutex);
148146
for (auto ptr = listeners.begin(), end = listeners.end(); ptr != end; ptr++) {
@@ -162,6 +160,7 @@ void AdHocConnectionImpl::readPackets() {
162160
uint8_t *buffer = new uint8_t[MAXBUFFER];
163161
int channel = 0;
164162
int hr = 0;
163+
165164
while (hr == 0 && con_ != nullptr && !closed) {
166165
int read = 0;
167166
if (safePort->isClosed()) {

MavLinkCom/src/impl/AdHocConnectionImpl.hpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,10 +53,13 @@ class AdHocConnectionImpl {
5353
void unsubscribe(int id);
5454

5555
private:
56-
static std::shared_ptr<AdHocConnection> createConnection(const std::string &nodeName, std::shared_ptr<Port> port);
56+
template <typename PortType>
57+
static std::shared_ptr<AdHocConnection> createConnection(const std::string &nodeName,
58+
std::shared_ptr<PortType> port);
5759
void publishPackets();
5860
void readPackets();
5961
void drainQueue();
62+
6063
std::string name;
6164
std::shared_ptr<Port> port;
6265
std::shared_ptr<AdHocConnection> con_;
@@ -71,6 +74,7 @@ class AdHocConnectionImpl {
7174
int id;
7275
AdHocMessageHandler handler;
7376
};
77+
7478
std::vector<MessageHandlerEntry> listeners;
7579
std::vector<MessageHandlerEntry> snapshot;
7680
bool snapshot_stale;
@@ -88,6 +92,7 @@ class AdHocConnectionImpl {
8892
std::mutex telemetry_mutex_;
8993
std::unordered_set<uint8_t> ignored_messageids;
9094
};
95+
9196
} // namespace mavlinkcom_impl
9297

9398
#endif

MavLinkCom/src/impl/MavLinkVideoStreamImpl.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111
using namespace mavlink_utils;
1212

1313
using namespace mavlinkcom_impl;
14+
1415
//================================= CLIENT ==============================================================
1516

1617
MavLinkVideoClientImpl::MavLinkVideoClientImpl(int localSystemId, int localComponentId)

MavLinkCom/src/serial_com/Port.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33

44
#ifndef PORT_H
55
#define PORT_H
6+
67
#include <stdint.h>
78

89
class Port {
@@ -23,4 +24,5 @@ class Port {
2324

2425
virtual ~Port() = default;
2526
};
27+
2628
#endif // !PORT_H

MavLinkCom/src/serial_com/SocketInit.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
#endif
1111

1212
using namespace mavlink_utils;
13+
1314
bool SocketInit::socket_initialized_ = false;
1415

1516
SocketInit::SocketInit() {

MavLinkCom/src/serial_com/SocketInit.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,4 +11,4 @@ class SocketInit {
1111
SocketInit();
1212
};
1313

14-
#endif
14+
#endif

MavLinkCom/src/serial_com/TcpClientPort.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,8 +5,8 @@
55
#include "SocketInit.hpp"
66
#include "Utils.hpp"
77
#include "wifi.h"
8-
#include <stdio.h>
9-
#include <string.h>
8+
#include <cstdio>
9+
#include <string>
1010

1111
using namespace mavlink_utils;
1212

0 commit comments

Comments
 (0)