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

mavlink / MAVSDK / 5041356744

pending completion
5041356744

push

github

GitHub
Merge pull request #1772 from mavlink/pr-split-mavlink-params

2216 of 2216 new or added lines in 34 files covered. (100.0%)

7715 of 24842 relevant lines covered (31.06%)

20.02 hits per line

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

90.0
/src/mavsdk/core/mavlink_parameter_cache.cpp
1
#include "mavlink_parameter_cache.h"
2

3
#include <algorithm>
4

5
namespace mavsdk {
6

7
MavlinkParameterCache::AddNewParamResult
8
MavlinkParameterCache::add_new_param(const std::string& param_id, ParamValue value, int16_t index)
64✔
9
{
10
    if (exists(param_id)) {
64✔
11
        return AddNewParamResult::AlreadyExists;
2✔
12
    }
13

14
    if (_all_params.size() + 1 > std::numeric_limits<int16_t>::max()) {
62✔
15
        return AddNewParamResult::TooManyParams;
×
16
    }
17

18
    _all_params.push_back(Param{
186✔
19
        param_id,
20
        std::move(value),
62✔
21
        (index != -1 ? static_cast<uint16_t>(index) : static_cast<uint16_t>(_all_params.size()))});
62✔
22
    return MavlinkParameterCache::AddNewParamResult::Ok;
62✔
23
}
24

25
MavlinkParameterCache::UpdateExistingParamResult
26
MavlinkParameterCache::update_existing_param(const std::string& param_id, ParamValue value)
13✔
27
{
28
    auto it = std::find_if(_all_params.begin(), _all_params.end(), [&](const auto& param) {
13✔
29
        return (param_id == param.id);
18✔
30
    });
13✔
31

32
    if (it == _all_params.end()) {
13✔
33
        return UpdateExistingParamResult::MissingParam;
1✔
34
    }
35

36
    if (!it->value.is_same_type(value)) {
12✔
37
        return MavlinkParameterCache::UpdateExistingParamResult::WrongType;
1✔
38
    } else {
39
        it->value.update_value_typesafe(value);
11✔
40
        return MavlinkParameterCache::UpdateExistingParamResult::Ok;
11✔
41
    }
42
}
43

44
std::vector<MavlinkParameterCache::Param>
45
MavlinkParameterCache::all_parameters(bool including_extended) const
125✔
46
{
47
    if (including_extended) {
125✔
48
        return _all_params;
50✔
49
    } else {
50
        // TODO: we might want to cache this
51
        std::vector<MavlinkParameterCache::Param> params_without_extended{};
150✔
52
        std::copy_if(
53
            _all_params.begin(),
54
            _all_params.end(),
55
            std::back_inserter(params_without_extended),
56
            [](auto& entry) { return !entry.value.needs_extended(); });
257✔
57

58
        return params_without_extended;
75✔
59
    }
60
}
61

62
std::map<std::string, ParamValue>
63
MavlinkParameterCache::all_parameters_map(bool including_extended) const
4✔
64
{
65
    std::map<std::string, ParamValue> mp{};
4✔
66
    if (including_extended) {
4✔
67
        for (const auto& param : _all_params) {
20✔
68
            mp.insert({param.id, param.value});
18✔
69
        }
70

71
    } else {
72
        for (const auto& param : _all_params) {
14✔
73
            if (param.value.needs_extended()) {
12✔
74
                continue;
×
75
            }
76
            mp.insert({param.id, param.value});
12✔
77
        }
78
    }
79

80
    return mp;
4✔
81
}
82

83
std::optional<MavlinkParameterCache::Param>
84
MavlinkParameterCache::param_by_id(const std::string& param_id, bool including_extended) const
55✔
85
{
86
    const auto& params = all_parameters(including_extended);
110✔
87

88
    for (const auto& param : params) {
70✔
89
        if (param.id == param_id) {
56✔
90
            return param;
41✔
91
        }
92
    }
93

94
    return {};
14✔
95
}
96

97
std::optional<MavlinkParameterCache::Param>
98
MavlinkParameterCache::param_by_index(uint16_t param_index, bool including_extended) const
4✔
99
{
100
    const auto& params = all_parameters(including_extended);
8✔
101
    if (param_index >= params.size()) {
4✔
102
        LogErr() << "param at " << (int)param_index << " out of bounds (" << params.size() << ")";
×
103
        return {};
×
104
    }
105

106
    const auto& param = params[param_index];
4✔
107
    // Check that the redundant index matches the actual vector index.
108
    assert(param.index == param_index);
4✔
109
    return {param};
4✔
110
}
111

112
uint16_t MavlinkParameterCache::count(bool including_extended) const
60✔
113
{
114
    const auto num = all_parameters(including_extended).size();
60✔
115
    assert(num < std::numeric_limits<uint16_t>::max());
60✔
116
    return static_cast<uint16_t>(num);
60✔
117
}
118

119
void MavlinkParameterCache::clear()
×
120
{
121
    _all_params.clear();
×
122
}
×
123

124
bool MavlinkParameterCache::exists(const std::string& param_id) const
64✔
125
{
126
    auto it = std::find_if(_all_params.begin(), _all_params.end(), [&](const auto& param) {
64✔
127
        return (param_id == param.id);
186✔
128
    });
64✔
129
    return it != _all_params.end();
64✔
130
}
131

132
std::optional<uint16_t> MavlinkParameterCache::next_missing_index(uint16_t count)
10✔
133
{
134
    // Extended doesn't matter here because we use this function in the sender
135
    // which is always either all extended or not.
136
    std::sort(_all_params.begin(), _all_params.end(), [](const auto& lhs, const auto& rhs) {
10✔
137
        return lhs.index < rhs.index;
61✔
138
    });
139

140
    for (unsigned i = 0; i < count; ++i) {
36✔
141
        if (_all_params.size() <= i) {
35✔
142
            // We have reached the end but it's not complete yet.
143
            return i;
5✔
144
        }
145
        if (_all_params[i].index > i) {
30✔
146
            // We have found a hole to fill.
147
            return i;
4✔
148
        }
149
    }
150
    return {};
1✔
151
}
152

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