• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

mavlink / MAVSDK / 18417543635

10 Oct 2025 08:22PM UTC coverage: 48.275% (+0.6%) from 47.661%
18417543635

Pull #2684

github

web-flow
Merge ba1aec5b0 into a58aaa9e1
Pull Request #2684: Re-connection fixes and system tests

274 of 282 new or added lines in 3 files covered. (97.16%)

24 existing lines in 2 files now uncovered.

17418 of 36081 relevant lines covered (48.27%)

496.56 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

84.62
/src/mavsdk/core/tcp_server_connection.cpp
1
#include "tcp_server_connection.h"
2
#include "log.h"
3

4
#include <cassert>
5
#include <fcntl.h>
6
#include <sstream>
7

8
#ifdef WINDOWS
9
#ifndef MINGW
10
#pragma comment(lib, "Ws2_32.lib") // Without this, Ws2_32.lib is not included in static library.
11
#endif
12
#include <Windows.h>
13
#include <Winsock2.h>
14
#include <ws2tcpip.h>
15
#else
16
#include <netinet/in.h>
17
#include <sys/select.h>
18
#include <sys/socket.h>
19
#include <arpa/inet.h>
20
#include <errno.h>
21
#include <netdb.h>
22
#endif
23

24
namespace mavsdk {
25
TcpServerConnection::TcpServerConnection(
4✔
26
    Connection::ReceiverCallback receiver_callback,
27
    Connection::LibmavReceiverCallback libmav_receiver_callback,
28
    MavsdkImpl& mavsdk_impl,
29
    std::string local_ip,
30
    int local_port,
31
    ForwardingOption forwarding_option) :
4✔
32
    Connection(
33
        std::move(receiver_callback),
4✔
34
        std::move(libmav_receiver_callback),
4✔
35
        mavsdk_impl,
36
        forwarding_option),
37
    _local_ip(std::move(local_ip)),
4✔
38
    _local_port(local_port)
12✔
39
{}
4✔
40

41
TcpServerConnection::~TcpServerConnection()
8✔
42
{
43
    stop();
4✔
44
}
8✔
45

46
ConnectionResult TcpServerConnection::start()
4✔
47
{
48
    if (!start_mavlink_receiver()) {
4✔
49
        return ConnectionResult::ConnectionsExhausted;
×
50
    }
51

52
    if (!start_libmav_receiver()) {
4✔
53
        return ConnectionResult::ConnectionsExhausted;
×
54
    }
55

56
#ifdef WINDOWS
57
    WSADATA wsa;
58
    if (WSAStartup(MAKEWORD(2, 2), &wsa) != 0) {
59
        LogErr() << "Error: Winsock failed, error: " << get_socket_error_string(WSAGetLastError());
60
        return ConnectionResult::SocketError;
61
    }
62
#endif
63

64
    _server_socket_fd.reset(socket(AF_INET, SOCK_STREAM, 0));
4✔
65
    if (_server_socket_fd.empty()) {
4✔
UNCOV
66
        LogErr() << "socket error: " << strerror(errno);
×
UNCOV
67
        return ConnectionResult::SocketError;
×
68
    }
69

70
    // Allow reuse of address to avoid "Address already in use" errors
71
    int yes = 1;
4✔
72
#ifdef WINDOWS
73
    setsockopt(_server_socket_fd.get(), SOL_SOCKET, SO_REUSEADDR, (const char*)&yes, sizeof(yes));
74
#else
75
    setsockopt(_server_socket_fd.get(), SOL_SOCKET, SO_REUSEADDR, &yes, sizeof(yes));
4✔
76
#endif
77

78
    sockaddr_in server_addr{};
4✔
79
    server_addr.sin_family = AF_INET;
4✔
80
    server_addr.sin_addr.s_addr = INADDR_ANY;
4✔
81
    server_addr.sin_port = htons(_local_port);
4✔
82

83
    if (bind(
4✔
84
            _server_socket_fd.get(),
85
            reinterpret_cast<sockaddr*>(&server_addr),
86
            sizeof(server_addr)) < 0) {
4✔
UNCOV
87
        LogErr() << "bind error: " << strerror(errno);
×
UNCOV
88
        return ConnectionResult::SocketError;
×
89
    }
90

91
    if (listen(_server_socket_fd.get(), 3) < 0) {
4✔
UNCOV
92
        LogErr() << "listen error: " << strerror(errno);
×
UNCOV
93
        return ConnectionResult::SocketError;
×
94
    }
95

96
    // Set receive timeout cross-platform
97
    const unsigned timeout_ms = 500;
4✔
98

99
#if defined(WINDOWS)
100
    setsockopt(
101
        _server_socket_fd.get(),
102
        SOL_SOCKET,
103
        SO_RCVTIMEO,
104
        (const char*)&timeout_ms,
105
        sizeof(timeout_ms));
106
    setsockopt(
107
        _client_socket_fd.get(),
108
        SOL_SOCKET,
109
        SO_RCVTIMEO,
110
        (const char*)&timeout_ms,
111
        sizeof(timeout_ms));
112
#else
113
    struct timeval tv;
114
    tv.tv_sec = 0;
4✔
115
    tv.tv_usec = timeout_ms * 1000;
4✔
116
    setsockopt(_server_socket_fd.get(), SOL_SOCKET, SO_RCVTIMEO, (const void*)&tv, sizeof(tv));
4✔
117
    setsockopt(_client_socket_fd.get(), SOL_SOCKET, SO_RCVTIMEO, (const void*)&tv, sizeof(tv));
4✔
118
#endif
119

120
    _accept_receive_thread =
121
        std::make_unique<std::thread>(&TcpServerConnection::accept_client, this);
4✔
122

123
    return ConnectionResult::Success;
4✔
124
}
125

126
ConnectionResult TcpServerConnection::stop()
4✔
127
{
128
    _should_exit = true;
4✔
129

130
    if (_accept_receive_thread && _accept_receive_thread->joinable()) {
4✔
131
        _accept_receive_thread->join();
4✔
132
        _accept_receive_thread.reset();
4✔
133
    }
134

135
    _client_socket_fd.close();
4✔
136
    _server_socket_fd.close();
4✔
137

138
    // We need to stop this after stopping the receive thread, otherwise
139
    // it can happen that we interfere with the parsing of a message.
140
    stop_mavlink_receiver();
4✔
141

142
    return ConnectionResult::Success;
4✔
143
}
144

145
std::pair<bool, std::string> TcpServerConnection::send_message(const mavlink_message_t& message)
37✔
146
{
147
    // Convert message to raw bytes and use common send path
148
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
149
    uint16_t buffer_len = mavlink_msg_to_send_buffer(buffer, &message);
37✔
150

151
    assert(buffer_len <= MAVLINK_MAX_PACKET_LEN);
37✔
152

153
    return send_raw_bytes(reinterpret_cast<const char*>(buffer), buffer_len);
37✔
154
}
155

156
void TcpServerConnection::accept_client()
4✔
157
{
158
#ifdef WINDOWS
159
    // Set server socket to non-blocking
160
    u_long iMode = 1;
161
    int iResult = ioctlsocket(_server_socket_fd.get(), FIONBIO, &iMode);
162
    if (iResult != 0) {
163
        LogErr() << "ioctlsocket failed with error: " << get_socket_error_string(WSAGetLastError());
164
    }
165
#else
166
    // Set server socket to non-blocking
167
    int flags = fcntl(_server_socket_fd.get(), F_GETFL, 0);
4✔
168
    fcntl(_server_socket_fd.get(), F_SETFL, flags | O_NONBLOCK);
4✔
169
#endif
170

171
    while (!_should_exit) {
11✔
172
        fd_set readfds;
173
        FD_ZERO(&readfds);
119✔
174
        FD_SET(_server_socket_fd.get(), &readfds);
7✔
175

176
        // Set timeout to 1 second
177
        timeval timeout;
178
        timeout.tv_sec = 1;
7✔
179
        timeout.tv_usec = 0;
7✔
180

181
        const int activity =
182
            select(_server_socket_fd.get() + 1, &readfds, nullptr, nullptr, &timeout);
7✔
183

184
        if (activity < 0 && errno != EINTR) {
7✔
NEW
185
            LogErr() << "select error: " << strerror(errno);
×
186
            continue;
2✔
187
        }
188

189
        if (activity == 0) {
7✔
190
            // Timeout, no incoming connection
191
            continue;
2✔
192
        }
193

194
        if (FD_ISSET(_server_socket_fd.get(), &readfds)) {
5✔
195
            sockaddr_in client_addr{};
5✔
196
            socklen_t client_addr_len = sizeof(client_addr);
5✔
197

198
            {
199
                _client_socket_fd.reset(accept(
5✔
200
                    _server_socket_fd.get(),
201
                    reinterpret_cast<sockaddr*>(&client_addr),
202
                    &client_addr_len));
203
            }
204
            if (_client_socket_fd.empty()) {
5✔
NEW
205
                if (_should_exit) {
×
NEW
206
                    return;
×
207
                }
NEW
208
                LogErr() << "accept error: " << strerror(errno);
×
NEW
209
                continue;
×
210
            }
211

212
            receive();
5✔
213
        }
214
    }
215
}
216

217
void TcpServerConnection::receive()
5✔
218
{
219
    std::array<char, 2048> buffer{};
5✔
220

221
    bool dataReceived = false;
5✔
222
    while (!dataReceived && !_should_exit) {
49✔
223
        const auto recv_len = recv(_client_socket_fd.get(), buffer.data(), buffer.size(), 0);
47✔
224

225
#ifdef WINDOWS
226
        if (recv_len == SOCKET_ERROR) {
227
            // On Windows, on the first try, select says there is something
228
            // but recv doesn't succeed yet, and we just need to try again.
229
            if (WSAGetLastError() == WSAEWOULDBLOCK) {
230
                std::this_thread::sleep_for(std::chrono::milliseconds(10));
231
                continue;
232
            }
233
            // And at the end, we get an abort that we can silently ignore.
234
            if (WSAGetLastError() == WSAECONNABORTED) {
235
                return;
236
            }
237
        }
238
#else
239
        if (recv_len < 0) {
47✔
240
            // On macOS we presumably see the same thing, and have to try again.
241
            if (errno == EAGAIN) {
13✔
242
                std::this_thread::sleep_for(std::chrono::milliseconds(10));
13✔
243
                continue;
13✔
244
            }
245

246
            // Connection reset - if shutting down, exit quietly; otherwise log and exit
UNCOV
247
            if (errno == ECONNRESET) {
×
UNCOV
248
                if (!_should_exit) {
×
UNCOV
249
                    LogErr() << "recv failed: " << strerror(errno);
×
250
                }
251
                return;
3✔
252
            }
253

UNCOV
254
            LogErr() << "recv failed: " << strerror(errno);
×
UNCOV
255
            return;
×
256
        }
257
#endif
258

259
        if (recv_len == 0) {
34✔
260
            // Client disconnected, close the socket and go back to accept new connections
261
            LogInfo() << "TCP client disconnected, waiting for new connection...";
3✔
262
            _client_socket_fd.close();
3✔
263
            return;
3✔
264
        }
265

266
        _mavlink_receiver->set_new_datagram(buffer.data(), static_cast<int>(recv_len));
31✔
267

268
        // Parse all mavlink messages in one data packet. Once exhausted, we'll exit while.
269
        while (_mavlink_receiver->parse_message()) {
64✔
270
            receive_message(_mavlink_receiver->get_last_message(), this);
33✔
271
        }
272

273
        // Also parse with libmav if available
274
        if (_libmav_receiver) {
31✔
275
            _libmav_receiver->set_new_datagram(buffer.data(), static_cast<int>(recv_len));
31✔
276

277
            while (_libmav_receiver->parse_message()) {
62✔
278
                receive_libmav_message(_libmav_receiver->get_last_message(), this);
31✔
279
            }
280
        }
281
    }
282
}
283

284
std::pair<bool, std::string> TcpServerConnection::send_raw_bytes(const char* bytes, size_t length)
37✔
285
{
286
    // Basic implementation for TCP server connections
287
    std::pair<bool, std::string> result;
37✔
288

289
#if !defined(MSG_NOSIGNAL)
290
    auto flags = 0;
291
#else
292
    auto flags = MSG_NOSIGNAL;
37✔
293
#endif
294

295
    const auto send_len = send(_client_socket_fd.get(), bytes, length, flags);
37✔
296

297
    if (send_len != static_cast<std::remove_cv_t<decltype(send_len)>>(length)) {
37✔
298
        // Broken pipe is expected during shutdown, don't log it
299
        std::stringstream ss;
1✔
300
#ifdef WINDOWS
301
        int err = WSAGetLastError();
302
        ss << "Send failure: " << get_socket_error_string(err);
303
        if (err != WSAECONNRESET || !_should_exit) {
304
            LogErr() << ss.str();
305
        }
306
#else
307
        ss << "Send failure: " << strerror(errno);
1✔
308
        if (errno != EPIPE || !_should_exit) {
1✔
309
            LogErr() << ss.str();
1✔
310
        }
311
#endif
312
        result.first = false;
1✔
313
        result.second = ss.str();
1✔
314
        return result;
1✔
315
    }
1✔
316

317
    result.first = true;
36✔
318
    return result;
36✔
319
}
320

321
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc