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

mavlink / MAVSDK / 17122957150

21 Aug 2025 09:31AM UTC coverage: 47.242% (+0.03%) from 47.211%
17122957150

Pull #2646

github

web-flow
Merge bc2b15b0e into 1bb1e1b56
Pull Request #2646: mavlink_direct: handle NaN correctly

118 of 223 new or added lines in 3 files covered. (52.91%)

16 existing lines in 5 files now uncovered.

16777 of 35513 relevant lines covered (47.24%)

442.08 hits per line

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

78.17
/src/mavsdk/core/udp_connection.cpp
1
#include "udp_connection.h"
2
#include "log.h"
3

4
#ifdef WINDOWS
5
#include <winsock2.h>
6
#include <Ws2tcpip.h> // For InetPton
7
#undef SOCKET_ERROR // conflicts with ConnectionResult::SocketError
8
#ifndef MINGW
9
#pragma comment(lib, "Ws2_32.lib") // Without this, Ws2_32.lib is not included in static library.
10
#endif
11
#else
12
#include <netinet/in.h>
13
#include <sys/socket.h>
14
#include <sys/time.h>
15
#include <arpa/inet.h>
16
#include <errno.h>
17
#endif
18

19
#include <algorithm>
20
#include <utility>
21
#include <sstream>
22

23
#ifdef WINDOWS
24
#define GET_ERROR(_x) WSAGetLastError()
25
#else
26
#define GET_ERROR(_x) strerror(_x)
27
#endif
28

29
namespace mavsdk {
30

31
UdpConnection::UdpConnection(
116✔
32
    Connection::ReceiverCallback receiver_callback,
33
    Connection::LibmavReceiverCallback libmav_receiver_callback,
34
    MavsdkImpl& mavsdk_impl,
35
    std::string local_ip,
36
    int local_port_number,
37
    ForwardingOption forwarding_option) :
116✔
38
    Connection(
39
        std::move(receiver_callback),
116✔
40
        std::move(libmav_receiver_callback),
116✔
41
        mavsdk_impl,
42
        forwarding_option),
43
    _local_ip(std::move(local_ip)),
116✔
44
    _local_port_number(local_port_number)
348✔
45
{}
116✔
46

47
UdpConnection::~UdpConnection()
232✔
48
{
49
    // If no one explicitly called stop before, we should at least do it.
50
    stop();
116✔
51
}
232✔
52

53
ConnectionResult UdpConnection::start()
116✔
54
{
55
    if (!start_mavlink_receiver()) {
116✔
56
        return ConnectionResult::ConnectionsExhausted;
×
57
    }
58

59
    if (!start_libmav_receiver()) {
116✔
60
        return ConnectionResult::ConnectionsExhausted;
×
61
    }
62

63
    ConnectionResult ret = setup_port();
116✔
64
    if (ret != ConnectionResult::Success) {
116✔
65
        return ret;
×
66
    }
67

68
    start_recv_thread();
116✔
69

70
    return ConnectionResult::Success;
116✔
71
}
72

73
ConnectionResult UdpConnection::setup_port()
116✔
74
{
75
#ifdef WINDOWS
76
    WSADATA wsa;
77
    if (WSAStartup(MAKEWORD(2, 2), &wsa) != 0) {
78
        LogErr() << "Error: Winsock failed, error: %d", WSAGetLastError();
79
        return ConnectionResult::SocketError;
80
    }
81
#endif
82

83
    _socket_fd.reset(socket(AF_INET, SOCK_DGRAM, 0));
116✔
84

85
    if (_socket_fd.empty()) {
116✔
86
        LogErr() << "socket error" << GET_ERROR(errno);
×
87
        return ConnectionResult::SocketError;
×
88
    }
89

90
    struct sockaddr_in addr{};
116✔
91
    addr.sin_family = AF_INET;
116✔
92
    if (inet_pton(AF_INET, _local_ip.c_str(), &(addr.sin_addr)) != 1) {
116✔
93
        LogErr() << "inet_pton failure for address: " << _local_ip;
×
94
        return ConnectionResult::SocketError;
×
95
    }
96
    addr.sin_port = htons(_local_port_number);
116✔
97

98
    if (bind(_socket_fd.get(), reinterpret_cast<sockaddr*>(&addr), sizeof(addr)) != 0) {
116✔
99
        LogErr() << "bind error: " << GET_ERROR(errno);
×
100
        return ConnectionResult::BindError;
×
101
    }
102

103
    // Set receive timeout cross-platform
104
    const unsigned timeout_ms = 500;
116✔
105

106
#if defined(WINDOWS)
107
    setsockopt(
108
        _socket_fd.get(), SOL_SOCKET, SO_RCVTIMEO, (const char*)&timeout_ms, sizeof(timeout_ms));
109
#else
110
    struct timeval tv;
111
    tv.tv_sec = 0;
116✔
112
    tv.tv_usec = timeout_ms * 1000;
116✔
113
    setsockopt(_socket_fd.get(), SOL_SOCKET, SO_RCVTIMEO, (const void*)&tv, sizeof(tv));
116✔
114
#endif
115

116
    return ConnectionResult::Success;
116✔
117
}
118

119
void UdpConnection::start_recv_thread()
116✔
120
{
121
    _recv_thread = std::make_unique<std::thread>(&UdpConnection::receive, this);
116✔
122
}
116✔
123

124
ConnectionResult UdpConnection::stop()
116✔
125
{
126
    _should_exit = true;
116✔
127

128
    if (_recv_thread) {
116✔
129
        _recv_thread->join();
116✔
130
        _recv_thread.reset();
116✔
131
    }
132

133
    _socket_fd.close();
116✔
134

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

139
    return ConnectionResult::Success;
116✔
140
}
141

142
std::pair<bool, std::string> UdpConnection::send_message(const mavlink_message_t& message)
2,280✔
143
{
144
    // Convert message to raw bytes and use common send path
145
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
146
    uint16_t buffer_len = mavlink_msg_to_send_buffer(buffer, &message);
2,280✔
147
    return send_raw_bytes(reinterpret_cast<const char*>(buffer), buffer_len);
2,279✔
148
}
149

150
std::pair<bool, std::string> UdpConnection::send_raw_bytes(const char* bytes, size_t length)
2,277✔
151
{
152
    std::pair<bool, std::string> result;
2,277✔
153

154
    std::lock_guard<std::mutex> lock(_remote_mutex);
2,270✔
155

156
    // Remove inactive remotes before sending messages
157
    auto now = std::chrono::steady_clock::now();
2,280✔
158

159
    _remotes.erase(
4,546✔
160
        std::remove_if(
2,268✔
161
            _remotes.begin(),
162
            _remotes.end(),
163
            [&now, this](const Remote& remote) {
2,266✔
164
                const auto elapsed = now - remote.last_activity;
2,266✔
165
                const bool inactive = elapsed > REMOTE_TIMEOUT;
2,274✔
166

167
                const bool should_remove = inactive && remote.remote_option == RemoteOption::Found;
2,271✔
168

169
                // We can cleanup old/previous remotes if we have
170
                if (should_remove) {
2,271✔
171
                    LogInfo() << "Removing inactive remote: " << remote.ip << ":"
×
172
                              << remote.port_number;
×
173
                }
174

175
                return should_remove;
2,271✔
176
            }),
177
        _remotes.end());
2,278✔
178

179
    if (_remotes.size() == 0) {
2,271✔
180
        result.first = false;
4✔
181
        result.second = "no remotes";
4✔
182
        return result;
4✔
183
    }
184

185
    // Send the raw bytes to all the remotes. A remote is a UDP endpoint
186
    // identified by its <ip, port>. This means that if we have two
187
    // systems on two different endpoints, then messages directed towards
188
    // only one system will be sent to both remotes. The systems are
189
    // then expected to ignore messages that are not directed to them.
190

191
    // For multiple remotes, we ignore errors, for just one, we bubble it up.
192
    result.first = true;
2,265✔
193

194
    for (auto& remote : _remotes) {
4,540✔
195
        struct sockaddr_in dest_addr{};
2,272✔
196
        dest_addr.sin_family = AF_INET;
2,272✔
197

198
        if (inet_pton(AF_INET, remote.ip.c_str(), &dest_addr.sin_addr.s_addr) != 1) {
2,272✔
199
            std::stringstream ss;
×
200
            ss << "inet_pton failure for: " << remote.ip << ":" << remote.port_number;
×
201
            LogErr() << ss.str();
×
202
            result.first = false;
×
203
            if (!result.second.empty()) {
×
204
                result.second += ", ";
×
205
            }
206
            result.second += ss.str();
×
207
            continue;
×
208
        }
×
209
        dest_addr.sin_port = htons(remote.port_number);
2,273✔
210

211
        const auto send_len = sendto(
2,273✔
212
            _socket_fd.get(),
213
            bytes,
214
            length,
215
            0,
216
            reinterpret_cast<const sockaddr*>(&dest_addr),
217
            sizeof(dest_addr));
218

219
        if (send_len != static_cast<std::remove_cv_t<decltype(send_len)>>(length)) {
2,275✔
220
            std::stringstream ss;
×
221
            ss << "sendto failure: " << GET_ERROR(errno) << " for: " << remote.ip << ":"
×
222
               << remote.port_number;
×
223
            LogErr() << ss.str();
×
224
            result.first = false;
×
225
            if (!result.second.empty()) {
×
226
                result.second += ", ";
×
227
            }
228
            result.second += ss.str();
×
229
            continue;
×
230
        }
×
231
    }
232

233
    return result;
2,276✔
234
}
2,280✔
235

236
void UdpConnection::add_remote_to_keep(const std::string& remote_ip, const int remote_port)
58✔
237
{
238
    add_remote_impl(remote_ip, remote_port, 0, RemoteOption::Fixed);
58✔
239
}
58✔
240

241
void UdpConnection::add_remote_impl(
2,333✔
242
    const std::string& remote_ip,
243
    const int remote_port,
244
    const uint8_t remote_sysid,
245
    RemoteOption remote_option)
246
{
247
    std::lock_guard<std::mutex> lock(_remote_mutex);
2,333✔
248
    Remote new_remote;
2,332✔
249
    new_remote.ip = remote_ip;
2,328✔
250
    new_remote.port_number = remote_port;
2,331✔
251
    new_remote.last_activity = std::chrono::steady_clock::now();
2,331✔
252
    new_remote.remote_option = remote_option;
2,329✔
253

254
    auto existing_remote =
255
        std::find_if(_remotes.begin(), _remotes.end(), [&new_remote](Remote& remote) {
2,329✔
256
            return remote == new_remote;
2,215✔
257
        });
258

259
    if (existing_remote == _remotes.end()) {
2,333✔
260
        // System with sysid 0 is a bit special: it is a placeholder for a connection initiated
261
        // by MAVSDK. As such, it should not be advertised as a newly discovered system.
262
        if (static_cast<int>(remote_sysid) != 0) {
116✔
263
            LogInfo() << "New system on: " << new_remote.ip << ":" << new_remote.port_number
116✔
264
                      << " (with system ID: " << static_cast<int>(remote_sysid) << ")";
58✔
265
        }
266
        _remotes.push_back(new_remote);
116✔
267
    } else {
268
        // Update the timestamp for the existing remote
269
        existing_remote->last_activity = std::chrono::steady_clock::now();
2,213✔
270
    }
271
}
2,326✔
272

273
void UdpConnection::receive()
116✔
274
{
275
    // Enough for MTU 1500 bytes.
276
    char buffer[2048];
277

278
    while (!_should_exit) {
2,708✔
279
        struct sockaddr_in src_addr = {};
2,591✔
280
        socklen_t src_addr_len = sizeof(src_addr);
2,591✔
281
        const auto recv_len = recvfrom(
2,591✔
282
            _socket_fd.get(),
283
            buffer,
284
            sizeof(buffer),
285
            0,
286
            reinterpret_cast<struct sockaddr*>(&src_addr),
287
            &src_addr_len);
288

289
        if (recv_len == 0) {
2,593✔
290
            // This can happen when shutdown is called on the socket,
291
            // therefore we check _should_exit again.
292
            continue;
318✔
293
        }
294

295
        if (recv_len < 0) {
2,593✔
296
            // This happens on destruction when _socket_fd.close() is called,
297
            // therefore be quiet.
298
            // LogErr() << "recvfrom error: " << GET_ERROR(errno);
299
            continue;
318✔
300
        }
301

302
        _mavlink_receiver->set_new_datagram(buffer, static_cast<int>(recv_len));
2,275✔
303

304
        // Parse all mavlink messages in one datagram. Once exhausted, we'll exit while.
305
        while (_mavlink_receiver->parse_message()) {
4,548✔
306
            const uint8_t sysid = _mavlink_receiver->get_last_message().sysid;
2,274✔
307

308
            if (sysid != 0) {
2,270✔
309
                char ip_str[INET_ADDRSTRLEN];
310
                if (inet_ntop(AF_INET, &src_addr.sin_addr, ip_str, INET_ADDRSTRLEN) != nullptr) {
2,270✔
311
                    add_remote_impl(ip_str, ntohs(src_addr.sin_port), sysid, RemoteOption::Found);
2,275✔
312
                } else {
UNCOV
313
                    LogErr() << "inet_ntop failure for: " << strerror(errno);
×
314
                }
315
            }
316

317
            // Handle parsed message
318
            receive_message(_mavlink_receiver->get_last_message(), this);
2,272✔
319
        }
320

321
        // Also parse with libmav if available
322
        if (_libmav_receiver) {
2,275✔
323
            _libmav_receiver->set_new_datagram(buffer, static_cast<int>(recv_len));
2,275✔
324

325
            while (_libmav_receiver->parse_message()) {
4,543✔
326
                receive_libmav_message(_libmav_receiver->get_last_message(), this);
2,273✔
327
            }
328
        }
329
    }
330
}
107✔
331

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

© 2025 Coveralls, Inc