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

mavlink / MAVSDK / 20440875926

22 Dec 2025 06:41PM UTC coverage: 48.058% (+0.1%) from 47.959%
20440875926

push

github

web-flow
Merge pull request #2739 from mavlink/pr-param-changes

param_server: add error when params are provided too late

77 of 80 new or added lines in 4 files covered. (96.25%)

10 existing lines in 3 files now uncovered.

17734 of 36901 relevant lines covered (48.06%)

466.52 hits per line

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

67.86
/src/mavsdk/plugins/param_server/param_server_impl.cpp
1
#include "param_server_impl.h"
2
#include "callback_list.tpp"
3
#include <thread>
4
#include <chrono>
5

6
namespace mavsdk {
7

8
template class CallbackList<ParamServer::IntParam>;
9
template class CallbackList<ParamServer::FloatParam>;
10
template class CallbackList<ParamServer::CustomParam>;
11

12
ParamServerImpl::ParamServerImpl(std::shared_ptr<ServerComponent> server_component) :
10✔
13
    ServerPluginImplBase(server_component)
10✔
14
{
15
    // FIXME: this plugin should support various component IDs
16
    _server_component_impl->register_plugin(this);
10✔
17
}
10✔
18

19
ParamServerImpl::~ParamServerImpl()
20✔
20
{
21
    _server_component_impl->unregister_plugin(this);
10✔
22
}
20✔
23

24
void ParamServerImpl::init() {}
10✔
25

26
void ParamServerImpl::deinit()
10✔
27
{
28
    // Ensure synchronous cleanup - keep trying until all callbacks are unregistered
29
    auto& param_server = _server_component_impl->mavlink_parameter_server();
10✔
30
    param_server.unsubscribe_all_params_changed(this);
10✔
31

32
    // Give a brief moment for any deferred unsubscriptions to be processed
33
    // This prevents use-after-free if callbacks are still executing
34
    std::this_thread::sleep_for(std::chrono::milliseconds(10));
10✔
35

36
    // Clear our callback lists to ensure no pending callbacks exist
37
    _changed_param_int_callbacks.clear();
10✔
38
    _changed_param_float_callbacks.clear();
10✔
39
    _changed_param_custom_callbacks.clear();
10✔
40
}
10✔
41

42
ParamServer::Result ParamServerImpl::set_protocol(bool extended_protocol)
×
43
{
44
    _server_component_impl->mavlink_parameter_server().set_extended_protocol(extended_protocol);
×
45
    return ParamServer::Result::Success;
×
46
}
47

48
std::pair<ParamServer::Result, int32_t> ParamServerImpl::retrieve_param_int(std::string name) const
2✔
49
{
50
    auto result =
51
        _server_component_impl->mavlink_parameter_server().retrieve_server_param_int(name);
2✔
52

53
    if (result.first == MavlinkParameterServer::Result::Ok) {
2✔
54
        return {ParamServer::Result::Success, result.second};
2✔
55
    } else {
56
        return {ParamServer::Result::NotFound, -1};
×
57
    }
58
}
59

60
ParamServer::Result ParamServerImpl::provide_param_int(std::string name, int32_t value)
53✔
61
{
62
    if (name.size() > 16) {
53✔
63
        return ParamServer::Result::ParamNameTooLong;
×
64
    }
65

66
    if (_server_component_impl->mavlink_parameter_server().params_locked_down()) {
53✔
67
        return ParamServer::Result::ParamProvidedTooLate;
1✔
68
    }
69

70
    const auto ret =
71
        _server_component_impl->mavlink_parameter_server().provide_server_param_int(name, value);
52✔
72
    if (ret == MavlinkParameterServer::Result::Ok) {
52✔
73
        _server_component_impl->mavlink_parameter_server().subscribe_param_int_changed(
36✔
74
            name,
75
            [name, this](int32_t new_value) { _changed_param_int_callbacks({name, new_value}); },
21✔
76
            this);
77
    }
78
    return result_from_mavlink_parameter_server_result(ret);
52✔
79
}
80

81
std::pair<ParamServer::Result, float> ParamServerImpl::retrieve_param_float(std::string name) const
2✔
82
{
83
    const auto result =
84
        _server_component_impl->mavlink_parameter_server().retrieve_server_param_float(name);
2✔
85

86
    if (result.first == MavlinkParameterServer::Result::Ok) {
2✔
87
        return {ParamServer::Result::Success, result.second};
2✔
88
    } else {
89
        return {ParamServer::Result::NotFound, NAN};
×
90
    }
91
}
92

93
ParamServer::Result ParamServerImpl::provide_param_float(std::string name, float value)
11✔
94
{
95
    if (name.size() > 16) {
11✔
96
        return ParamServer::Result::ParamNameTooLong;
×
97
    }
98

99
    if (_server_component_impl->mavlink_parameter_server().params_locked_down()) {
11✔
NEW
100
        return ParamServer::Result::ParamProvidedTooLate;
×
101
    }
102

103
    const auto ret =
104
        _server_component_impl->mavlink_parameter_server().provide_server_param_float(name, value);
11✔
105
    if (ret == MavlinkParameterServer::Result::Ok) {
11✔
106
        _server_component_impl->mavlink_parameter_server().subscribe_param_float_changed(
10✔
107
            name,
108
            [name, this](float new_value) { _changed_param_float_callbacks({name, new_value}); },
3✔
109
            this);
110
    }
111
    return result_from_mavlink_parameter_server_result(ret);
11✔
112
}
113

114
std::pair<ParamServer::Result, std::string>
115
ParamServerImpl::retrieve_param_custom(std::string name) const
2✔
116
{
117
    const auto result =
118
        _server_component_impl->mavlink_parameter_server().retrieve_server_param_custom(name);
2✔
119

120
    if (result.first == MavlinkParameterServer::Result::Ok) {
2✔
121
        return {ParamServer::Result::Success, result.second};
2✔
122
    } else {
123
        return {ParamServer::Result::NotFound, {}};
×
124
    }
125
}
2✔
126

127
ParamServer::Result
128
ParamServerImpl::provide_param_custom(std::string name, const std::string& value)
8✔
129
{
130
    if (name.size() > 16) {
8✔
131
        return ParamServer::Result::ParamNameTooLong;
×
132
    }
133

134
    const auto ret =
135
        _server_component_impl->mavlink_parameter_server().provide_server_param_custom(name, value);
8✔
136
    if (ret == MavlinkParameterServer::Result::Ok) {
8✔
137
        _server_component_impl->mavlink_parameter_server().subscribe_param_custom_changed(
8✔
138
            name,
139
            [name, this](const std::string& new_value) {
2✔
140
                _changed_param_custom_callbacks({name, new_value});
2✔
141
            },
2✔
142
            this);
143
    }
144
    return result_from_mavlink_parameter_server_result(ret);
8✔
145
}
146

147
ParamServer::AllParams ParamServerImpl::retrieve_all_params() const
2✔
148
{
149
    auto tmp = _server_component_impl->mavlink_parameter_server().retrieve_all_server_params();
2✔
150

151
    ParamServer::AllParams res{};
2✔
152

153
    for (auto const& param_pair : tmp) {
6✔
154
        if (param_pair.second.is<float>()) {
4✔
155
            ParamServer::FloatParam tmp_param;
2✔
156
            tmp_param.name = param_pair.first;
2✔
157
            tmp_param.value = param_pair.second.get<float>();
2✔
158
            res.float_params.push_back(tmp_param);
2✔
159
        } else if (param_pair.second.is<int32_t>()) {
4✔
160
            ParamServer::IntParam tmp_param;
2✔
161
            tmp_param.name = param_pair.first;
2✔
162
            tmp_param.value = param_pair.second.get<int32_t>();
2✔
163
            res.int_params.push_back(tmp_param);
2✔
164
        }
2✔
165
    }
166

167
    return res;
2✔
168
}
2✔
169

170
ParamServer::ChangedParamIntHandle
171
ParamServerImpl::subscribe_changed_param_int(const ParamServer::ChangedParamIntCallback& callback)
×
172
{
173
    return _changed_param_int_callbacks.subscribe(callback);
×
174
}
175

176
void ParamServerImpl::unsubscribe_changed_param_int(ParamServer::ChangedParamIntHandle handle)
×
177
{
178
    _changed_param_int_callbacks.unsubscribe(handle);
×
179
}
×
180

181
ParamServer::ChangedParamFloatHandle ParamServerImpl::subscribe_changed_param_float(
×
182
    const ParamServer::ChangedParamFloatCallback& callback)
183
{
184
    return _changed_param_float_callbacks.subscribe(callback);
×
185
}
186

187
void ParamServerImpl::unsubscribe_changed_param_float(ParamServer::ChangedParamFloatHandle handle)
×
188
{
189
    _changed_param_float_callbacks.unsubscribe(handle);
×
190
}
×
191

192
ParamServer::ChangedParamCustomHandle ParamServerImpl::subscribe_changed_param_custom(
×
193
    const ParamServer::ChangedParamCustomCallback& callback)
194
{
195
    return _changed_param_custom_callbacks.subscribe(callback);
×
196
}
197

198
void ParamServerImpl::unsubscribe_changed_param_custom(ParamServer::ChangedParamCustomHandle handle)
×
199
{
200
    _changed_param_custom_callbacks.unsubscribe(handle);
×
201
}
×
202

203
ParamServer::Result
204
ParamServerImpl::result_from_mavlink_parameter_server_result(MavlinkParameterServer::Result result)
71✔
205
{
206
    switch (result) {
71✔
207
        case MavlinkParameterServer::Result::Ok:
71✔
208
        case MavlinkParameterServer::Result::OkExistsAlready:
209
            return ParamServer::Result::Success;
71✔
210
        case MavlinkParameterServer::Result::NotFound:
×
211
            return ParamServer::Result::NotFound;
×
212
        case MavlinkParameterServer::Result::ParamNameTooLong:
×
213
            return ParamServer::Result::ParamNameTooLong;
×
214
        case MavlinkParameterServer::Result::WrongType:
×
215
            return ParamServer::Result::WrongType;
×
216
        case MavlinkParameterServer::Result::ParamValueTooLong:
×
217
            return ParamServer::Result::ParamValueTooLong;
×
218
        default:
×
219
            LogErr() << "Unknown param error";
×
220
            return ParamServer::Result::Unknown;
×
221
    }
222
}
223

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