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

mavlink / MAVSDK / 4899817366

pending completion
4899817366

Pull #1772

github

GitHub
Merge c0bb90862 into e4e9c71dd
Pull Request #1772: Refactor MAVLinkParameters into client and server classes

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

7708 of 24812 relevant lines covered (31.07%)

19.96 hits per line

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

0.0
/src/mavsdk/plugins/component_information/component_information_impl.cpp
1
#include "component_information_impl.h"
2
#include "fs.h"
3
#include "callback_list.tpp"
4

5
#include <utility>
6
#include <fstream>
7
#include <json/json.h>
8

9
namespace mavsdk {
10

11
template class CallbackList<ComponentInformation::FloatParamUpdate>;
12

13
ComponentInformationImpl::ComponentInformationImpl(System& system) : PluginImplBase(system)
×
14
{
15
    _system_impl->register_plugin(this);
×
16
}
×
17

18
ComponentInformationImpl::ComponentInformationImpl(std::shared_ptr<System> system) :
×
19
    PluginImplBase(std::move(system))
×
20
{
21
    _system_impl->register_plugin(this);
×
22
}
×
23

24
ComponentInformationImpl::~ComponentInformationImpl()
×
25
{
26
    _system_impl->unregister_plugin(this);
×
27
}
×
28

29
void ComponentInformationImpl::init() {}
×
30

31
void ComponentInformationImpl::deinit() {}
×
32

33
void ComponentInformationImpl::enable()
×
34
{
35
    // TODO: iterate through components!
36

37
    _system_impl->request_message().request(
×
38
        MAVLINK_MSG_ID_COMPONENT_INFORMATION,
39
        MAV_COMP_ID_PATHPLANNER,
40
        [this](auto&& result, auto&& message) { receive_component_information(result, message); });
×
41
}
×
42

43
void ComponentInformationImpl::disable() {}
×
44

45
void ComponentInformationImpl::receive_component_information(
×
46
    MavlinkCommandSender::Result result, const mavlink_message_t& message)
47
{
48
    if (result != MavlinkCommandSender::Result::Success) {
×
49
        LogWarn() << "Requesting component information failed with " << static_cast<int>(result);
×
50
        return;
×
51
    }
52

53
    mavlink_component_information_t component_information;
×
54
    mavlink_msg_component_information_decode(&message, &component_information);
×
55

56
    component_information
57
        .general_metadata_uri[sizeof(component_information.general_metadata_uri) - 1] = '\0';
×
58
    const auto general_metadata_uri = std::string(component_information.general_metadata_uri);
×
59

60
    download_file_async(
×
61
        general_metadata_uri, [this](std::string path) { parse_metadata_file(path); });
×
62
}
63

64
void ComponentInformationImpl::download_file_async(
×
65
    const std::string& uri, std::function<void(std::string path)> callback)
66
{
67
    // TODO: check CRC
68

69
    if (uri.empty()) {
×
70
        LogErr() << "No component information URI provided";
×
71
        return;
×
72

73
    } else if (uri.find("mftp://") == 0) {
×
74
        LogDebug() << "Found mftp URI, using MAVLink FTP to download file";
×
75

76
        const auto path = uri.substr(strlen("mftp://"));
×
77

78
        const auto maybe_tmp_path = create_tmp_directory("mavsdk-component-information-tmp-files");
×
79
        const auto path_to_download = maybe_tmp_path ? maybe_tmp_path.value() : "./";
×
80

81
        _system_impl->mavlink_ftp().download_async(
×
82
            path,
83
            path_to_download,
84
            [path_to_download, callback, path](
×
85
                MavlinkFtp::ClientResult download_result, MavlinkFtp::ProgressData progress_data) {
86
                if (download_result == MavlinkFtp::ClientResult::Next) {
×
87
                    LogDebug() << "File download progress: " << progress_data.bytes_transferred
×
88
                               << '/' << progress_data.total_bytes;
×
89
                } else {
90
                    LogDebug() << "File download ended with result " << download_result;
×
91
                    if (download_result == MavlinkFtp::ClientResult::Success) {
×
92
                        LogDebug() << "Received file " << path_to_download + "/" + path;
×
93
                        callback(path_to_download + "/" + path);
×
94
                    }
95
                }
96
            });
×
97
    } else if (uri.find("http://") == 0 || uri.find("https://") == 0) {
×
98
        LogWarn() << "Download using http(s) not implemented yet";
×
99
    } else {
100
        LogWarn() << "Unknown URI protocol";
×
101
    }
102
}
103

104
void ComponentInformationImpl::parse_metadata_file(const std::string& path)
×
105
{
106
    std::ifstream f(path);
×
107
    if (f.bad()) {
×
108
        LogErr() << "Could not open json metadata file.";
×
109
        return;
×
110
    }
111

112
    Json::Value metadata;
×
113
    f >> metadata;
×
114

115
    if (!metadata.isMember("version")) {
×
116
        LogErr() << "version not found";
×
117
        return;
×
118
    }
119

120
    if (metadata["version"].asInt() != 1) {
×
121
        LogWarn() << "version " << metadata["version"].asInt() << " not supported";
×
122
    }
123

124
    if (!metadata.isMember("metadataTypes")) {
×
125
        LogErr() << "metadataTypes not found";
×
126
        return;
×
127
    }
128

129
    for (auto& metadata_type : metadata["metadataTypes"]) {
×
130
        if (!metadata_type.isMember("type")) {
×
131
            LogErr() << "type missing";
×
132
            return;
×
133
        }
134
        if (!metadata_type.isMember("uri")) {
×
135
            LogErr() << "uri missing";
×
136
            return;
×
137
        }
138

139
        if (metadata_type["type"].asInt() == COMP_METADATA_TYPE_PARAMETER) {
×
140
            download_file_async(
×
141
                metadata_type["uri"].asString(), [this](const std::string& parameter_file_path) {
×
142
                    LogDebug() << "Found parameter file at: " << parameter_file_path;
×
143
                    parse_parameter_file(parameter_file_path);
×
144
                });
×
145
        }
146
    }
147
}
148

149
void ComponentInformationImpl::parse_parameter_file(const std::string& path)
×
150
{
151
    std::ifstream f(path);
×
152
    if (f.bad()) {
×
153
        LogErr() << "Could not open json parameter file.";
×
154
        return;
×
155
    }
156

157
    Json::Value parameters;
×
158
    f >> parameters;
×
159

160
    if (!parameters.isMember("version")) {
×
161
        LogErr() << "version not found";
×
162
        return;
×
163
    }
164

165
    if (parameters["version"].asInt() != 1) {
×
166
        LogWarn() << "version " << parameters["version"].asInt() << " not supported";
×
167
    }
168

169
    if (!parameters.isMember("parameters")) {
×
170
        LogErr() << "parameters not found";
×
171
        return;
×
172
    }
173

174
    std::lock_guard<std::mutex> lock(_mutex);
×
175
    _float_params.clear();
×
176

177
    for (auto& param : parameters["parameters"]) {
×
178
        if (!param.isMember("type")) {
×
179
            LogErr() << "type not found";
×
180
            return;
×
181
        }
182

183
        if (param["type"].asString() == "Float") {
×
184
            _float_params.push_back(ComponentInformation::FloatParam{
×
185
                param["name"].asString(),
×
186
                param["shortDesc"].asString(),
×
187
                param["longDesc"].asString(),
×
188
                param["units"].asString(),
×
189
                param["decimalPlaces"].asInt(),
×
190
                NAN,
191
                param["default"].asFloat(),
×
192
                param["min"].asFloat(),
×
193
                param["max"].asFloat()});
×
194

195
            const auto name = param["name"].asString();
×
196

197
            _system_impl->get_param_float_async(
×
198
                name,
199
                [this, name](MavlinkParameterSender::Result result, float value) {
×
200
                    get_float_param_result(name, result, value);
×
201
                },
×
202
                this);
203

204
            _system_impl->subscribe_param_float(
×
205
                name, [this, name](float value) { param_update(name, value); }, this);
×
206

207
        } else {
208
            LogWarn() << "Ignoring type " << param["type"].asString() << " for now.";
×
209
        }
210
    }
211
}
212

213
void ComponentInformationImpl::get_float_param_result(
×
214
    const std::string& name, MavlinkParameterSender::Result result, float value)
215
{
216
    if (result != MavlinkParameterSender::Result::Success) {
×
217
        LogWarn() << "Getting float param result: " << static_cast<int>(result);
×
218
        return;
×
219
    }
220

221
    std::lock_guard<std::mutex> lock(_mutex);
×
222
    for (auto& param : _float_params) {
×
223
        if (param.name == name) {
×
224
            param.start_value = value;
×
225
            LogDebug() << "Received value " << value << " for " << name;
×
226
        }
227
    }
228
}
229

230
void ComponentInformationImpl::param_update(const std::string& name, float new_value)
×
231
{
232
    std::lock_guard<std::mutex> lock(_mutex);
×
233

234
    for (auto& param : _float_params) {
×
235
        if (param.name == name) {
×
236
            param.start_value = new_value;
×
237
            LogDebug() << "Received value " << new_value << " for " << name;
×
238
        }
239
    }
240

241
    const auto param_update = ComponentInformation::FloatParamUpdate{name, new_value};
×
242

243
    _float_param_update_callbacks.queue(
×
244
        param_update, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
245
}
×
246

247
std::pair<ComponentInformation::Result, std::vector<ComponentInformation::FloatParam>>
248
ComponentInformationImpl::access_float_params()
×
249
{
250
    return {ComponentInformation::Result::Success, _float_params};
×
251
}
252

253
ComponentInformation::FloatParamHandle ComponentInformationImpl::subscribe_float_param(
×
254
    const ComponentInformation::FloatParamCallback& callback)
255
{
256
    std::lock_guard<std::mutex> lock(_mutex);
×
257
    return _float_param_update_callbacks.subscribe(callback);
×
258
}
259

260
void ComponentInformationImpl::unsubscribe_float_param(
×
261
    ComponentInformation::FloatParamHandle handle)
262
{
263
    std::lock_guard<std::mutex> lock(_mutex);
×
264
    _float_param_update_callbacks.unsubscribe(handle);
×
265
}
×
266

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