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

mavlink / MAVSDK / 16485391475

24 Jul 2025 01:13AM UTC coverage: 46.33% (+1.2%) from 45.096%
16485391475

push

github

web-flow
Merge pull request #2610 from mavlink/pr-add-libmavlike

Integrate parts of libmav into MAVSDK and add MavlinkDirect plugin

764 of 987 new or added lines in 14 files covered. (77.41%)

10 existing lines in 1 file now uncovered.

16272 of 35122 relevant lines covered (46.33%)

359.99 hits per line

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

77.57
/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
#ifndef WINDOWS
25
#define GET_ERROR(_x) strerror(_x)
26
#else
27
#define GET_ERROR(_x) WSAGetLastError()
28
#endif
29

30
namespace mavsdk {
31
TcpServerConnection::TcpServerConnection(
1✔
32
    Connection::ReceiverCallback receiver_callback,
33
    Connection::LibmavReceiverCallback libmav_receiver_callback,
34
    mav::MessageSet& message_set,
35
    std::string local_ip,
36
    int local_port,
37
    ForwardingOption forwarding_option) :
1✔
38
    Connection(
39
        std::move(receiver_callback),
1✔
40
        std::move(libmav_receiver_callback),
1✔
41
        message_set,
42
        forwarding_option),
43
    _local_ip(std::move(local_ip)),
1✔
44
    _local_port(local_port)
4✔
45
{}
1✔
46

47
TcpServerConnection::~TcpServerConnection()
2✔
48
{
49
    stop();
1✔
50
}
2✔
51

52
ConnectionResult TcpServerConnection::start()
1✔
53
{
54
    if (!start_mavlink_receiver()) {
1✔
55
        return ConnectionResult::ConnectionsExhausted;
×
56
    }
57

58
    if (!start_libmav_receiver()) {
1✔
NEW
59
        return ConnectionResult::ConnectionsExhausted;
×
60
    }
61

62
#ifdef WINDOWS
63
    WSADATA wsa;
64
    if (WSAStartup(MAKEWORD(2, 2), &wsa) != 0) {
65
        LogErr() << "Error: Winsock failed, error: " << WSAGetLastError();
66
        return ConnectionResult::SocketError;
67
    }
68
#endif
69

70
    _server_socket_fd.reset(socket(AF_INET, SOCK_STREAM, 0));
1✔
71
    if (_server_socket_fd.empty()) {
1✔
72
        LogErr() << "socket error: " << GET_ERROR(errno);
×
73
        return ConnectionResult::SocketError;
×
74
    }
75

76
    sockaddr_in server_addr{};
1✔
77
    server_addr.sin_family = AF_INET;
1✔
78
    server_addr.sin_addr.s_addr = INADDR_ANY;
1✔
79
    server_addr.sin_port = htons(_local_port);
1✔
80

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

89
    if (listen(_server_socket_fd.get(), 3) < 0) {
1✔
90
        LogErr() << "listen error: " << GET_ERROR(errno);
×
91
        return ConnectionResult::SocketError;
×
92
    }
93

94
    // Set receive timeout cross-platform
95
    const unsigned timeout_ms = 500;
1✔
96

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

118
    _accept_receive_thread =
1✔
119
        std::make_unique<std::thread>(&TcpServerConnection::accept_client, this);
1✔
120

121
    return ConnectionResult::Success;
1✔
122
}
123

124
ConnectionResult TcpServerConnection::stop()
1✔
125
{
126
    _should_exit = true;
1✔
127

128
    if (_accept_receive_thread && _accept_receive_thread->joinable()) {
1✔
129
        _accept_receive_thread->join();
1✔
130
        _accept_receive_thread.reset();
1✔
131
    }
132

133
    _client_socket_fd.close();
1✔
134
    _server_socket_fd.close();
1✔
135

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

140
    return ConnectionResult::Success;
1✔
141
}
142

143
std::pair<bool, std::string> TcpServerConnection::send_message(const mavlink_message_t& message)
7✔
144
{
145
    std::pair<bool, std::string> result;
7✔
146

147
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
7✔
148
    uint16_t buffer_len = mavlink_msg_to_send_buffer(buffer, &message);
7✔
149

150
    assert(buffer_len <= MAVLINK_MAX_PACKET_LEN);
7✔
151

152
#if !defined(MSG_NOSIGNAL)
153
    auto flags = 0;
154
#else
155
    auto flags = MSG_NOSIGNAL;
7✔
156
#endif
157

158
    const auto send_len =
159
        send(_client_socket_fd.get(), reinterpret_cast<const char*>(buffer), buffer_len, flags);
7✔
160

161
    if (send_len != buffer_len) {
7✔
162
        std::stringstream ss;
×
163
        ss << "Send failure: " << GET_ERROR(errno);
×
164
        LogErr() << ss.str();
×
165
        result.first = false;
×
166
        result.second = ss.str();
×
167
        return result;
×
168
    }
×
169

170
    result.first = true;
7✔
171
    return result;
7✔
172
}
173

174
void TcpServerConnection::accept_client()
1✔
175
{
176
#ifdef WINDOWS
177
    // Set server socket to non-blocking
178
    u_long iMode = 1;
179
    int iResult = ioctlsocket(_server_socket_fd.get(), FIONBIO, &iMode);
180
    if (iResult != 0) {
181
        LogErr() << "ioctlsocket failed with error: " << WSAGetLastError();
182
    }
183
#else
184
    // Set server socket to non-blocking
185
    int flags = fcntl(_server_socket_fd.get(), F_GETFL, 0);
1✔
186
    fcntl(_server_socket_fd.get(), F_SETFL, flags | O_NONBLOCK);
1✔
187
#endif
188

189
    while (!_should_exit) {
2✔
190
        fd_set readfds;
1✔
191
        FD_ZERO(&readfds);
17✔
192
        FD_SET(_server_socket_fd.get(), &readfds);
1✔
193

194
        // Set timeout to 1 second
195
        timeval timeout;
1✔
196
        timeout.tv_sec = 1;
1✔
197
        timeout.tv_usec = 0;
1✔
198

199
        const int activity =
200
            select(_server_socket_fd.get() + 1, &readfds, nullptr, nullptr, &timeout);
1✔
201

202
        if (activity < 0 && errno != EINTR) {
1✔
203
            LogErr() << "select error: " << GET_ERROR(errno);
×
204
            continue;
×
205
        }
206

207
        if (activity == 0) {
1✔
208
            // Timeout, no incoming connection
209
            continue;
×
210
        }
211

212
        if (FD_ISSET(_server_socket_fd.get(), &readfds)) {
1✔
213
            sockaddr_in client_addr{};
1✔
214
            socklen_t client_addr_len = sizeof(client_addr);
1✔
215

216
            _client_socket_fd.reset(accept(
1✔
217
                _server_socket_fd.get(),
218
                reinterpret_cast<sockaddr*>(&client_addr),
219
                &client_addr_len));
220
            if (_client_socket_fd.empty()) {
1✔
221
                if (_should_exit) {
×
222
                    return;
×
223
                }
224
                LogErr() << "accept error: " << GET_ERROR(errno);
×
225
                continue;
×
226
            }
227

228
            receive();
1✔
229
        }
230
    }
231
}
232

233
void TcpServerConnection::receive()
1✔
234
{
235
    std::array<char, 2048> buffer{};
1✔
236

237
    bool dataReceived = false;
1✔
238
    while (!dataReceived && !_should_exit) {
7,821✔
239
        const auto recv_len = recv(_client_socket_fd.get(), buffer.data(), buffer.size(), 0);
7,820✔
240

241
#ifdef WINDOWS
242
        if (recv_len == SOCKET_ERROR) {
243
            // On Windows, on the first try, select says there is something
244
            // but recv doesn't succeed yet, and we just need to try again.
245
            if (WSAGetLastError() == WSAEWOULDBLOCK) {
246
                std::this_thread::sleep_for(std::chrono::milliseconds(10));
247
                continue;
248
            }
249
            // And at the end, we get an abort that we can silently ignore.
250
            if (WSAGetLastError() == WSAECONNABORTED) {
251
                return;
252
            }
253
        }
254
#else
255
        if (recv_len < 0) {
7,820✔
256
            // On macOS we presumably see the same thing, and have to try again.
257
            if (errno == EAGAIN) {
2✔
258
                std::this_thread::sleep_for(std::chrono::milliseconds(10));
2✔
259
                continue;
2✔
260
            }
261

262
            LogErr() << "recv failed: " << GET_ERROR(errno);
×
263
            return;
×
264
        }
265
#endif
266

267
        if (recv_len == 0) {
7,818✔
268
            continue;
7,807✔
269
        }
270

271
        _mavlink_receiver->set_new_datagram(buffer.data(), static_cast<int>(recv_len));
11✔
272

273
        // Parse all mavlink messages in one data packet. Once exhausted, we'll exit while.
274
        while (_mavlink_receiver->parse_message()) {
23✔
275
            receive_message(_mavlink_receiver->get_last_message(), this);
12✔
276
        }
277
    }
278
}
279

280
} // 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