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

mavlink / MAVSDK / 19215993270

09 Nov 2025 11:20PM UTC coverage: 48.296% (-0.03%) from 48.329%
19215993270

push

github

web-flow
Merge pull request #2708 from mavlink/pr-mavsdk-server-usage

Fix connection usage for mavsdk_server

17630 of 36504 relevant lines covered (48.3%)

464.12 hits per line

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

87.93
/src/mavsdk/core/connection.cpp
1
#include "connection.h"
2

3
#include <memory>
4
#include <utility>
5
#include "mavsdk_impl.h"
6
#include "log.h"
7

8
#ifdef WINDOWS
9
#include <winsock2.h>
10
#endif
11

12
namespace mavsdk {
13

14
std::atomic<unsigned> Connection::_forwarding_connections_count = 0;
15

16
Connection::Connection(
140✔
17
    ReceiverCallback receiver_callback,
18
    LibmavReceiverCallback libmav_receiver_callback,
19
    MavsdkImpl& mavsdk_impl,
20
    ForwardingOption forwarding_option) :
140✔
21
    _receiver_callback(std::move(receiver_callback)),
140✔
22
    _libmav_receiver_callback(std::move(libmav_receiver_callback)),
140✔
23
    _mavsdk_impl(mavsdk_impl),
140✔
24
    _mavlink_receiver(),
140✔
25
    _libmav_receiver(),
140✔
26
    _forwarding_option(forwarding_option)
280✔
27
{
28
    // Insert system ID 0 in all connections for broadcast.
29
    _system_ids.insert(0);
140✔
30

31
    if (forwarding_option == ForwardingOption::ForwardingOn) {
140✔
32
        _forwarding_connections_count++;
6✔
33
    }
34

35
    if (const char* env_p = std::getenv("MAVSDK_MAVLINK_DIRECT_DEBUGGING")) {
140✔
36
        if (std::string(env_p) == "1") {
×
37
            _debugging = true;
×
38
        }
39
    }
40
}
140✔
41

42
Connection::~Connection()
140✔
43
{
44
    // Just in case a specific connection didn't call it already.
45
    stop_mavlink_receiver();
140✔
46
    stop_libmav_receiver();
140✔
47
    _receiver_callback = {};
140✔
48
    _libmav_receiver_callback = {};
140✔
49
}
140✔
50

51
bool Connection::start_mavlink_receiver()
140✔
52
{
53
    _mavlink_receiver = std::make_unique<MavlinkReceiver>();
140✔
54
    return true;
140✔
55
}
56

57
void Connection::stop_mavlink_receiver()
278✔
58
{
59
    if (_mavlink_receiver) {
278✔
60
        _mavlink_receiver.reset();
140✔
61
    }
62
}
278✔
63

64
bool Connection::start_libmav_receiver()
140✔
65
{
66
    _libmav_receiver = std::make_unique<LibmavReceiver>(_mavsdk_impl);
140✔
67
    return true;
140✔
68
}
69

70
void Connection::stop_libmav_receiver()
140✔
71
{
72
    if (_libmav_receiver) {
140✔
73
        _libmav_receiver.reset();
140✔
74
    }
75
}
140✔
76

77
void Connection::receive_libmav_message(
2,374✔
78
    const Mavsdk::MavlinkMessage& message, Connection* connection)
79
{
80
    // Register system ID when receiving a message from a new system.
81
    if (_system_ids.find(message.system_id) == _system_ids.end()) {
2,374✔
82
        _system_ids.insert(message.system_id);
×
83
    }
84

85
    if (_debugging) {
2,367✔
86
        LogDebug() << "Connection::receive_libmav_message: " << message.message_name
×
87
                   << " from system " << message.system_id;
×
88
    }
89

90
    if (_libmav_receiver_callback) {
2,367✔
91
        if (_debugging) {
2,370✔
92
            LogDebug() << "Calling libmav receiver callback for: " << message.message_name;
×
93
        }
94
        _libmav_receiver_callback(message, connection);
2,370✔
95
    } else {
96
        LogWarn() << "No libmav receiver callback set!";
×
97
    }
98
}
2,372✔
99

100
void Connection::receive_message(mavlink_message_t& message, Connection* connection)
2,378✔
101
{
102
    // Register system ID when receiving a message from a new system.
103
    if (_system_ids.find(message.sysid) == _system_ids.end()) {
2,378✔
104
        _system_ids.insert(message.sysid);
142✔
105
    }
106
    _receiver_callback(message, connection);
2,376✔
107
}
2,378✔
108

109
bool Connection::should_forward_messages() const
36✔
110
{
111
    return _forwarding_option == ForwardingOption::ForwardingOn;
36✔
112
}
113

114
unsigned Connection::forwarding_connections_count()
86✔
115
{
116
    return _forwarding_connections_count;
86✔
117
}
118

119
bool Connection::has_system_id(uint8_t system_id)
1,731✔
120
{
121
    return _system_ids.find(system_id) != _system_ids.end();
1,731✔
122
}
123

124
#ifdef WINDOWS
125
std::string get_socket_error_string(int error_code)
126
{
127
    if (error_code == 0) {
128
        return "";
129
    }
130

131
    LPVOID lpMsgBuf = nullptr;
132
    DWORD bufLen = FormatMessage(
133
        FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM | FORMAT_MESSAGE_IGNORE_INSERTS,
134
        NULL,
135
        error_code,
136
        MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT),
137
        (LPTSTR)&lpMsgBuf,
138
        0,
139
        NULL);
140

141
    if (bufLen) {
142
        LPCSTR lpMsgStr = (LPCSTR)lpMsgBuf;
143
        std::string result(lpMsgStr, lpMsgStr + bufLen);
144
        LocalFree(lpMsgBuf);
145

146
        // Remove trailing newline if present
147
        if (!result.empty() && result[result.length() - 1] == '\n') {
148
            result.erase(result.length() - 1);
149
        }
150
        if (!result.empty() && result[result.length() - 1] == '\r') {
151
            result.erase(result.length() - 1);
152
        }
153

154
        return result;
155
    }
156

157
    return std::to_string(error_code);
158
}
159
#endif
160

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