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

mavlink / MAVSDK / 23911409490

02 Apr 2026 04:40PM UTC coverage: 50.475% (+1.4%) from 49.029%
23911409490

push

github

web-flow
Merge pull request #2833 from bansiesta/v3-cherry-picks

Backport recent main fixes and features to v3

632 of 815 new or added lines in 29 files covered. (77.55%)

34 existing lines in 11 files now uncovered.

19249 of 38136 relevant lines covered (50.47%)

671.0 hits per line

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

93.51
/src/system_tests/camera_definition.cpp
1
#include "mavsdk.h"
2
#include "plugins/camera/camera.h"
3
#include "plugins/camera_server/camera_server.h"
4
#include "plugins/ftp_server/ftp_server.h"
5
#include <future>
6
#include <mutex>
7
#include <thread>
8
#include <gtest/gtest.h>
9

10
using namespace mavsdk;
11

12
// Wait for camera list to be populated and the definition to be fetched and parsed.
13
// Returns true if a non-empty list of setting options is available within the timeout.
14
static bool wait_for_camera_definition(
2✔
15
    Camera& camera, std::chrono::milliseconds timeout_ms, size_t expected_settings)
16
{
17
    const auto deadline = std::chrono::steady_clock::now() + timeout_ms;
2✔
18

19
    // Wait for camera list first
20
    while (std::chrono::steady_clock::now() < deadline) {
6✔
21
        if (camera.camera_list().cameras.size() > 0) {
6✔
22
            break;
2✔
23
        }
24
        std::this_thread::sleep_for(std::chrono::milliseconds(100));
4✔
25
    }
26

27
    if (camera.camera_list().cameras.empty()) {
2✔
NEW
28
        return false;
×
29
    }
30

31
    const int component_id = camera.camera_list().cameras[0].component_id;
2✔
32

33
    while (std::chrono::steady_clock::now() < deadline) {
2✔
34
        auto [result, options] = camera.get_possible_setting_options(component_id);
2✔
35
        if (result == Camera::Result::Success && options.size() == expected_settings) {
2✔
36
            return true;
2✔
37
        }
NEW
38
        std::this_thread::sleep_for(std::chrono::milliseconds(200));
×
39
    }
2✔
40

NEW
41
    return false;
×
42
}
43

44
static std::shared_ptr<System>
45
wait_for_camera_system(Mavsdk& mavsdk_groundstation, std::chrono::seconds timeout)
2✔
46
{
47
    auto prom = std::make_shared<std::promise<std::shared_ptr<System>>>();
2✔
48
    auto fut = prom->get_future();
2✔
49
    auto flag = std::make_shared<std::once_flag>();
2✔
50

51
    auto handle =
52
        mavsdk_groundstation.subscribe_on_new_system([&mavsdk_groundstation, prom, flag]() {
2✔
53
            const auto system = mavsdk_groundstation.systems().back();
2✔
54
            if (system->is_connected() && system->has_camera()) {
2✔
55
                std::call_once(*flag, [&]() { prom->set_value(system); });
4✔
56
            }
57
        });
2✔
58

59
    if (fut.wait_for(timeout) != std::future_status::ready) {
2✔
NEW
60
        mavsdk_groundstation.unsubscribe_on_new_system(handle);
×
NEW
61
        return nullptr;
×
62
    }
63

64
    mavsdk_groundstation.unsubscribe_on_new_system(handle);
2✔
65
    return fut.get();
2✔
66
}
2✔
67

68
TEST(SystemTest, CameraDefinitionUncompressed)
4✔
69
{
70
    Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}};
1✔
71
    Mavsdk mavsdk_camera{Mavsdk::Configuration{ComponentType::Camera}};
1✔
72

73
    ASSERT_EQ(
1✔
74
        mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17000"),
75
        ConnectionResult::Success);
1✔
76
    ASSERT_EQ(
1✔
77
        mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), ConnectionResult::Success);
1✔
78

79
    auto ftp_server = FtpServer{mavsdk_camera.server_component()};
1✔
80
    EXPECT_EQ(ftp_server.set_root_dir("src/mavsdk/plugins/camera/"), FtpServer::Result::Success);
1✔
81

82
    auto camera_server = CameraServer{mavsdk_camera.server_component()};
1✔
83
    CameraServer::Information information{};
1✔
84
    information.vendor_name = "UVC";
1✔
85
    information.model_name = "Logitech C270HD Webcam";
1✔
86
    information.firmware_version = "4.0.0";
1✔
87
    information.definition_file_version = 2;
1✔
88
    information.definition_file_uri = "mavlinkftp://uvc_camera.xml";
1✔
89
    EXPECT_EQ(camera_server.set_information(information), CameraServer::Result::Success);
1✔
90

91
    auto system = wait_for_camera_system(mavsdk_groundstation, std::chrono::seconds(2));
1✔
92
    ASSERT_NE(system, nullptr);
1✔
93

94
    auto camera = Camera{system};
1✔
95
    // With UVC XML defaults (WB_MODE=1 auto, EXP_MODE=3 aperture-priority) two settings
96
    // are excluded: WB_TEMP and EXP_ABSOLUTE — so 10 of the 12 control params are visible.
97
    ASSERT_TRUE(wait_for_camera_definition(camera, std::chrono::seconds(10), 10))
1✔
98
        << "Camera definition (uncompressed) was not loaded within timeout";
1✔
99
}
1✔
100

101
TEST(SystemTest, CameraDefinitionCompressedXz)
4✔
102
{
103
    Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}};
1✔
104
    Mavsdk mavsdk_camera{Mavsdk::Configuration{ComponentType::Camera}};
1✔
105

106
    ASSERT_EQ(
1✔
107
        mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17001"),
108
        ConnectionResult::Success);
1✔
109
    ASSERT_EQ(
1✔
110
        mavsdk_camera.add_any_connection("udpout://127.0.0.1:17001"), ConnectionResult::Success);
1✔
111

112
    auto ftp_server = FtpServer{mavsdk_camera.server_component()};
1✔
113
    EXPECT_EQ(ftp_server.set_root_dir("src/mavsdk/plugins/camera/"), FtpServer::Result::Success);
1✔
114

115
    auto camera_server = CameraServer{mavsdk_camera.server_component()};
1✔
116
    CameraServer::Information information{};
1✔
117
    information.vendor_name = "UVC";
1✔
118
    information.model_name = "Logitech C270HD Webcam";
1✔
119
    information.firmware_version = "4.0.0";
1✔
120
    information.definition_file_version =
1✔
121
        3; // different version to avoid cache collision with uncompressed test
122
    information.definition_file_uri = "mavlinkftp://uvc_camera.xml.xz";
1✔
123
    EXPECT_EQ(camera_server.set_information(information), CameraServer::Result::Success);
1✔
124

125
    auto system = wait_for_camera_system(mavsdk_groundstation, std::chrono::seconds(2));
1✔
126
    ASSERT_NE(system, nullptr);
1✔
127

128
    auto camera = Camera{system};
1✔
129
    // Same UVC XML defaults as the uncompressed test: 10 visible control settings.
130
    ASSERT_TRUE(wait_for_camera_definition(camera, std::chrono::seconds(10), 10))
1✔
131
        << "Camera definition (xz compressed) was not loaded within timeout";
1✔
132
}
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