• 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_server/component_information_server_impl.cpp
1
#include "component_information_server_impl.h"
2
#include "mavlink_request_message_handler.h"
3
#include "callback_list.tpp"
4

5
#include <algorithm>
6
#include <string>
7
#include <json/json.h>
8

9
namespace mavsdk {
10

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

13
ComponentInformationServerImpl::ComponentInformationServerImpl(
×
14
    std::shared_ptr<ServerComponent> server_component) :
×
15
    ServerPluginImplBase(server_component)
×
16
{
17
    // FIXME: allow other component IDs
18
    _server_component_impl->register_plugin(this);
×
19
}
×
20

21
ComponentInformationServerImpl::~ComponentInformationServerImpl()
×
22
{
23
    _server_component_impl->register_plugin(this);
×
24
}
×
25

26
void ComponentInformationServerImpl::init()
×
27
{
28
    _server_component_impl->mavlink_request_message_handler().register_handler(
×
29
        MAVLINK_MSG_ID_COMPONENT_INFORMATION,
30
        [this](uint8_t, uint8_t, MavlinkRequestMessageHandler::Params) {
×
31
            return process_component_information_requested();
×
32
        },
33
        this);
34
}
×
35

36
void ComponentInformationServerImpl::deinit()
×
37
{
38
    _server_component_impl->mavlink_request_message_handler().unregister_all_handlers(this);
×
39
}
×
40

41
ComponentInformationServer::Result
42
ComponentInformationServerImpl::provide_float_param(ComponentInformationServer::FloatParam param)
×
43
{
44
    std::lock_guard<std::mutex> lock(_mutex);
×
45

46
    if (std::find_if(
×
47
            _float_params.begin(),
48
            _float_params.end(),
49
            [&](ComponentInformationServer::FloatParam& existing_param) {
×
50
                return existing_param.name == param.name;
×
51
            }) != std::end(_float_params)) {
×
52
        return ComponentInformationServer::Result::DuplicateParam;
×
53
    }
54

55
    if (param.start_value > param.max_value || param.start_value < param.min_value) {
×
56
        return ComponentInformationServer::Result::InvalidParamStartValue;
×
57
    }
58

59
    if (param.default_value > param.max_value || param.default_value < param.min_value) {
×
60
        return ComponentInformationServer::Result::InvalidParamDefaultValue;
×
61
    }
62

63
    if (param.name.size() > 16) {
×
64
        return ComponentInformationServer::Result::InvalidParamName;
×
65
    }
66

67
    _float_params.push_back(param);
×
68

69
    update_json_files_with_lock();
×
70

71
    _server_component_impl->mavlink_parameter_receiver().provide_server_param_float(
×
72
        param.name, param.start_value);
×
73
    _server_component_impl->mavlink_parameter_receiver().subscribe_param_float_changed(
×
74
        param.name,
×
75
        [this, name = param.name](float new_value) { param_update(name, new_value); },
×
76
        this);
77

78
    return ComponentInformationServer::Result::Success;
×
79
}
80

81
ComponentInformationServer::FloatParamHandle ComponentInformationServerImpl::subscribe_float_param(
×
82
    const ComponentInformationServer::FloatParamCallback& callback)
83
{
84
    std::lock_guard<std::mutex> lock(_mutex);
×
85
    return _float_param_update_callbacks.subscribe(callback);
×
86
}
87

88
void ComponentInformationServerImpl::unsubscribe_float_param(
×
89
    ComponentInformationServer::FloatParamHandle handle)
90
{
91
    std::lock_guard<std::mutex> lock(_mutex);
×
92
    _float_param_update_callbacks.unsubscribe(handle);
×
93
}
×
94

95
void ComponentInformationServerImpl::param_update(const std::string& name, float new_value)
×
96
{
97
    std::lock_guard<std::mutex> lock(_mutex);
×
98
    ComponentInformationServer::FloatParamUpdate param_update{name, new_value};
×
99
    _float_param_update_callbacks.queue(param_update, [this](const auto& func) {
×
100
        _server_component_impl->call_user_callback(func);
×
101
    });
×
102
}
×
103

104
std::optional<MAV_RESULT> ComponentInformationServerImpl::process_component_information_requested()
×
105
{
106
    const char general_metadata_uri[100] = "mftp://general.json";
×
107
    const char peripherals_metadata_uri[100] = "";
×
108

109
    mavlink_message_t message;
×
110
    mavlink_msg_component_information_pack(
×
111
        _server_component_impl->get_own_system_id(),
×
112
        _server_component_impl->get_own_component_id(),
×
113
        &message,
114
        _server_component_impl->get_time().elapsed_ms(),
×
115
        0,
116
        general_metadata_uri,
117
        0,
118
        peripherals_metadata_uri);
119
    _server_component_impl->send_message(message);
×
120

121
    // FIXME: REMOVE again
122
    update_json_files_with_lock();
×
123

124
    return MAV_RESULT_ACCEPTED;
×
125
}
126

127
void ComponentInformationServerImpl::update_json_files_with_lock()
×
128
{
129
    auto parameter_file = generate_parameter_file();
×
130
    auto meta_file = generate_meta_file();
×
131

132
    // std::cout << "parameter: " << parameter_file << '\n';
133
    // std::cout << "meta: " << meta_file << '\n';
134

135
    // FIXME: needs refactoring
136
    //_server_component_impl->mavlink_ftp().write_tmp_file("general.json",
137
    // meta_file);
138
    //_server_component_impl->mavlink_ftp().write_tmp_file("parameter.json",
139
    // parameter_file);
140
}
×
141

142
std::string ComponentInformationServerImpl::generate_parameter_file()
×
143
{
144
    Json::Value root;
×
145
    root["version"] = 1;
×
146
    Json::Value parameters = Json::arrayValue;
×
147
    for (const auto& param : _float_params) {
×
148
        Json::Value parameter;
×
149
        parameter["name"] = param.name;
×
150
        parameter["type"] = "Float";
×
151
        parameter["shortDesc"] = param.short_description;
×
152
        parameter["longDesc"] = param.long_description;
×
153
        parameter["units"] = param.unit;
×
154
        parameter["decimalPlaces"] = param.decimal_places;
×
155
        parameter["min"] = static_cast<double>(param.min_value);
×
156
        parameter["max"] = static_cast<double>(param.max_value);
×
157
        parameter["default"] = static_cast<double>(param.default_value);
×
158
        parameters.append(parameter);
×
159
    }
160
    root["parameters"] = parameters;
×
161

162
    return root.toStyledString();
×
163
}
164

165
std::string ComponentInformationServerImpl::generate_meta_file()
×
166
{
167
    Json::Value root;
×
168
    root["version"] = 1;
×
169
    root["vendorName"] = "Vendor";
×
170
    root["modelName"] = "Model";
×
171
    root["firmwareVersion"] = "1.0.0.0";
×
172
    root["hardwareVersion"] = "1.0.0.0";
×
173
    Json::Value metadata_types = Json::arrayValue;
×
174
    Json::Value metadata_type;
×
175
    metadata_type["type"] = Json::Int{COMP_METADATA_TYPE_PARAMETER};
×
176
    metadata_type["uri"] = "mftp://parameter.json";
×
177
    metadata_type["fileCrc"] = 0; // TODO
×
178
    metadata_type["uriFallback"] = ""; // TODO
×
179
    metadata_type["fileCrcFallback"] = 0;
×
180
    metadata_types.append(metadata_type);
×
181
    root["metadataTypes"] = metadata_types;
×
182

183
    return root.toStyledString();
×
184
}
185

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