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

mavlink / MAVSDK / 16952411343

14 Aug 2025 12:13AM UTC coverage: 46.441% (+0.3%) from 46.171%
16952411343

push

github

web-flow
Merge pull request #2637 from mavlink/pr-forward-unknown-messages

Enable forwarding unknown messages

140 of 174 new or added lines in 6 files covered. (80.46%)

12 existing lines in 2 files now uncovered.

16258 of 35008 relevant lines covered (46.44%)

368.39 hits per line

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

98.21
/src/system_tests/mavlink_direct_forwarding.cpp
1
#include "log.h"
2
#include "mavsdk.h"
3
#include "plugins/mavlink_direct/mavlink_direct.h"
4
#include <chrono>
5
#include <thread>
6
#include <future>
7
#include <atomic>
8
#include <gtest/gtest.h>
9
#include <json/json.h>
10

11
using namespace mavsdk;
12

13
TEST(SystemTest, MavlinkDirectForwardingKnownMessage)
4✔
14
{
15
    // Test 3-instance message forwarding with a known standard message
16
    // Instance 1 (Sender) -> Instance 2 (Forwarder) -> Instance 3 (Receiver)
17

18
    // Instance 1: Sender (autopilot)
19
    Mavsdk mavsdk_sender{Mavsdk::Configuration{ComponentType::Autopilot}};
1✔
20

21
    // Instance 2: Forwarder (router with forwarding enabled)
22
    Mavsdk mavsdk_forwarder{Mavsdk::Configuration{ComponentType::CompanionComputer}};
1✔
23

24
    // Instance 3: Receiver (ground station)
25
    Mavsdk mavsdk_receiver{Mavsdk::Configuration{ComponentType::GroundStation}};
1✔
26

27
    // Set up connections: Sender -> Forwarder -> Receiver
28
    ASSERT_EQ(
1✔
29
        mavsdk_sender.add_any_connection("udpout://127.0.0.1:17010"), ConnectionResult::Success);
1✔
30
    ASSERT_EQ(
1✔
31
        mavsdk_forwarder.add_any_connection(
32
            "udpin://0.0.0.0:17010", ForwardingOption::ForwardingOn),
33
        ConnectionResult::Success);
1✔
34
    ASSERT_EQ(
1✔
35
        mavsdk_forwarder.add_any_connection(
36
            "udpout://127.0.0.1:17011", ForwardingOption::ForwardingOn),
37
        ConnectionResult::Success);
1✔
38
    ASSERT_EQ(
1✔
39
        mavsdk_receiver.add_any_connection("udpin://0.0.0.0:17011"), ConnectionResult::Success);
1✔
40

41
    LogInfo() << "Waiting for connections to establish...";
1✔
42
    std::this_thread::sleep_for(std::chrono::seconds(1));
1✔
43

44
    // Receiver discovers the sender system (autopilot) through the forwarder
45
    auto receiver_target_system = mavsdk_receiver.first_autopilot(10.0);
1✔
46
    ASSERT_TRUE(receiver_target_system.has_value());
1✔
47
    auto system = receiver_target_system.value();
1✔
48
    ASSERT_TRUE(system->has_autopilot());
1✔
49

50
    // Sender waits to discover ground station systems
51
    while (mavsdk_sender.systems().size() == 0) {
1✔
NEW
52
        std::this_thread::sleep_for(std::chrono::milliseconds(100));
×
53
    }
54

55
    // Get sender's view of the receiver systems (for sending)
56
    auto sender_target_system = mavsdk_sender.systems().at(0);
1✔
57

58
    // Create MavlinkDirect instances
59
    auto sender_mavlink_direct = MavlinkDirect{sender_target_system};
1✔
60
    auto receiver_mavlink_direct = MavlinkDirect{system};
1✔
61

62
    // Set up receiver subscription for a known message (GLOBAL_POSITION_INT)
63
    auto prom = std::promise<MavlinkDirect::MavlinkMessage>();
1✔
64
    auto fut = prom.get_future();
1✔
65

66
    auto handle = receiver_mavlink_direct.subscribe_message(
1✔
67
        "GLOBAL_POSITION_INT", [&prom](const MavlinkDirect::MavlinkMessage& message) {
2✔
68
            LogInfo() << "Receiver got forwarded known message: " << message.fields_json;
1✔
69
            prom.set_value(message);
1✔
70
        });
1✔
71

72
    // Send known message from sender
73
    LogInfo() << "Sending known GLOBAL_POSITION_INT message through forwarder...";
1✔
74
    MavlinkDirect::MavlinkMessage test_message;
1✔
75
    test_message.message_name = "GLOBAL_POSITION_INT";
1✔
76
    test_message.system_id = 1;
1✔
77
    test_message.component_id = 1;
1✔
78
    test_message.target_system = 0;
1✔
79
    test_message.target_component = 0;
1✔
80
    test_message.fields_json =
81
        R"({"time_boot_ms":12345,"lat":473977418,"lon":-1223974560,"alt":100500,"relative_alt":50250,"vx":100,"vy":-50,"vz":25,"hdg":18000})";
1✔
82

83
    EXPECT_EQ(MavlinkDirect::Result::Success, sender_mavlink_direct.send_message(test_message));
1✔
84

85
    // Wait for message to be received through the forwarder
86
    auto wait_result = fut.wait_for(std::chrono::seconds(3));
1✔
87

88
    ASSERT_EQ(wait_result, std::future_status::ready);
1✔
89

90
    auto received_message = fut.get();
1✔
91

92
    // Verify the forwarded message
93
    EXPECT_EQ(received_message.message_name, "GLOBAL_POSITION_INT");
1✔
94
    EXPECT_EQ(received_message.system_id, 1);
1✔
95
    EXPECT_EQ(received_message.component_id, 1);
1✔
96

97
    // Parse and verify JSON content
98
    Json::Value json;
1✔
99
    Json::Reader reader;
1✔
100
    ASSERT_TRUE(reader.parse(received_message.fields_json, json));
1✔
101

102
    // The JSON format may vary but should contain the message information
103
    // For now, just verify it's not empty and contains the message name
104
    EXPECT_FALSE(received_message.fields_json.empty());
1✔
105
    EXPECT_TRUE(received_message.fields_json.find("GLOBAL_POSITION_INT") != std::string::npos);
1✔
106

107
    receiver_mavlink_direct.unsubscribe_message(handle);
1✔
108
}
1✔
109

110
TEST(SystemTest, MavlinkDirectForwardingUnknownMessage)
4✔
111
{
112
    // Test 3-instance message forwarding where intermediate instance doesn't know the custom
113
    // message Instance 1 (Sender) -> Instance 2 (Forwarder) -> Instance 3 (Receiver) Only Instance
114
    // 1 and 3 have the custom XML loaded, Instance 2 must forward blindly
115

116
    // Instance 1: Sender (autopilot that knows custom message)
117
    Mavsdk mavsdk_sender{Mavsdk::Configuration{ComponentType::Autopilot}};
1✔
118

119
    // Instance 2: Forwarder (router that doesn't know custom message but forwards all)
120
    Mavsdk mavsdk_forwarder{Mavsdk::Configuration{ComponentType::CompanionComputer}};
1✔
121

122
    // Instance 3: Receiver (ground station that knows custom message)
123
    Mavsdk mavsdk_receiver{Mavsdk::Configuration{ComponentType::GroundStation}};
1✔
124

125
    // Set up connections: Sender -> Forwarder -> Receiver
126
    ASSERT_EQ(
1✔
127
        mavsdk_sender.add_any_connection("udpout://127.0.0.1:17006"), ConnectionResult::Success);
1✔
128
    ASSERT_EQ(
1✔
129
        mavsdk_forwarder.add_any_connection(
130
            "udpin://0.0.0.0:17006", ForwardingOption::ForwardingOn),
131
        ConnectionResult::Success);
1✔
132
    ASSERT_EQ(
1✔
133
        mavsdk_forwarder.add_any_connection(
134
            "udpout://127.0.0.1:17007", ForwardingOption::ForwardingOn),
135
        ConnectionResult::Success);
1✔
136
    ASSERT_EQ(
1✔
137
        mavsdk_receiver.add_any_connection("udpin://0.0.0.0:17007"), ConnectionResult::Success);
1✔
138

139
    // Define custom message that only sender and receiver will know about
140
    std::string custom_xml = R"(<?xml version="1.0"?>
1✔
141
<mavlink>
142
    <version>3</version>
143
    <dialect>0</dialect>
144
    <messages>
145
        <message id="421" name="CUSTOM_FORWARD_TEST">
146
            <description>Test message for forwarding unknown messages</description>
147
            <field type="uint32_t" name="test_id">Unique test identifier</field>
148
            <field type="uint16_t" name="sequence">Sequence number</field>
149
            <field type="uint8_t" name="status">Status code</field>
150
            <field type="char[32]" name="message">Status message</field>
151
        </message>
152
    </messages>
153
</mavlink>)";
154

155
    LogInfo() << "Waiting for connections to establish...";
1✔
156
    std::this_thread::sleep_for(std::chrono::seconds(1));
1✔
157

158
    // Receiver discovers the sender system (autopilot) through the forwarder
159
    auto receiver_target_system = mavsdk_receiver.first_autopilot(10.0);
1✔
160
    ASSERT_TRUE(receiver_target_system.has_value());
1✔
161
    auto system = receiver_target_system.value();
1✔
162
    ASSERT_TRUE(system->has_autopilot());
1✔
163

164
    // Sender waits to discover ground station systems
165
    while (mavsdk_sender.systems().size() == 0) {
1✔
NEW
166
        std::this_thread::sleep_for(std::chrono::milliseconds(100));
×
167
    }
168

169
    // Get sender's view of the receiver systems (for sending)
170
    auto sender_target_system = mavsdk_sender.systems().at(0);
1✔
171

172
    // Create MavlinkDirect instances: sender uses discovered system, receiver uses discovered
173
    // autopilot
174
    auto sender_mavlink_direct = MavlinkDirect{sender_target_system};
1✔
175
    auto receiver_mavlink_direct = MavlinkDirect{system};
1✔
176

177
    // Load custom XML only on sender and receiver (NOT on forwarder)
178
    EXPECT_EQ(MavlinkDirect::Result::Success, sender_mavlink_direct.load_custom_xml(custom_xml));
1✔
179
    EXPECT_EQ(MavlinkDirect::Result::Success, receiver_mavlink_direct.load_custom_xml(custom_xml));
1✔
180

181
    // Set up receiver subscription - handle potential duplicate messages
182
    std::atomic<bool> message_received{false};
1✔
183
    auto prom = std::promise<MavlinkDirect::MavlinkMessage>();
1✔
184
    auto fut = prom.get_future();
1✔
185

186
    auto handle = receiver_mavlink_direct.subscribe_message(
1✔
187
        "CUSTOM_FORWARD_TEST",
188
        [&prom, &message_received](const MavlinkDirect::MavlinkMessage& message) {
3✔
189
            LogInfo() << "Receiver got forwarded custom message: " << message.fields_json;
1✔
190
            if (!message_received.exchange(true)) {
1✔
191
                // Only set the promise once, even if we receive the message multiple times
192
                prom.set_value(message);
1✔
193
            }
194
        });
1✔
195

196
    // Send custom message from sender
197
    LogInfo() << "Sending custom message through forwarder...";
1✔
198
    MavlinkDirect::MavlinkMessage test_message;
1✔
199
    test_message.message_name = "CUSTOM_FORWARD_TEST";
1✔
200
    test_message.system_id = 1;
1✔
201
    test_message.component_id = 1;
1✔
202
    test_message.target_system = 0;
1✔
203
    test_message.target_component = 0;
1✔
204
    test_message.fields_json =
205
        R"({"test_id":12345,"sequence":1,"status":42,"message":"Hello through forwarder!"})";
1✔
206

207
    EXPECT_EQ(MavlinkDirect::Result::Success, sender_mavlink_direct.send_message(test_message));
1✔
208

209
    // Wait for message to be received through the forwarder
210
    LogInfo() << "Waiting for forwarded message...";
1✔
211
    auto wait_result = fut.wait_for(std::chrono::seconds(3));
1✔
212

213
    ASSERT_EQ(wait_result, std::future_status::ready);
1✔
214

215
    auto received_message = fut.get();
1✔
216

217
    // Verify the forwarded message
218
    EXPECT_EQ(received_message.message_name, "CUSTOM_FORWARD_TEST");
1✔
219
    EXPECT_EQ(received_message.system_id, 1);
1✔
220
    EXPECT_EQ(received_message.component_id, 1);
1✔
221

222
    // Parse and verify JSON content
223
    Json::Value json;
1✔
224
    Json::Reader reader;
1✔
225
    ASSERT_TRUE(reader.parse(received_message.fields_json, json));
1✔
226

227
    EXPECT_EQ(json["test_id"].asUInt(), 12345u);
1✔
228
    EXPECT_EQ(json["sequence"].asUInt(), 1u);
1✔
229
    EXPECT_EQ(json["status"].asUInt(), 42u);
1✔
230
    EXPECT_EQ(json["message"].asString(), "Hello through forwarder!");
2✔
231

232
    receiver_mavlink_direct.unsubscribe_message(handle);
1✔
233
}
1✔
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