• 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

70.83
/src/mavsdk/plugins/param_server/param_server_impl.cpp
1
#include "param_server_impl.h"
2

3
namespace mavsdk {
4

5
ParamServerImpl::ParamServerImpl(std::shared_ptr<ServerComponent> server_component) :
6✔
6
    ServerPluginImplBase(server_component)
6✔
7
{
8
    // FIXME: this plugin should support various component IDs
9
    _server_component_impl->register_plugin(this);
6✔
10
}
6✔
11

12
ParamServerImpl::~ParamServerImpl()
6✔
13
{
14
    _server_component_impl->unregister_plugin(this);
6✔
15
}
6✔
16

17
void ParamServerImpl::init() {}
6✔
18

19
void ParamServerImpl::deinit() {}
6✔
20

21
std::pair<ParamServer::Result, int32_t> ParamServerImpl::retrieve_param_int(std::string name) const
2✔
22
{
23
    auto result =
2✔
24
        _server_component_impl->mavlink_parameter_receiver().retrieve_server_param_int(name);
2✔
25

26
    if (result.first == MavlinkParameterReceiver::Result::Success) {
2✔
27
        return {ParamServer::Result::Success, result.second};
2✔
28
    } else {
29
        return {ParamServer::Result::NotFound, -1};
×
30
    }
31
}
32

33
ParamServer::Result ParamServerImpl::provide_param_int(std::string name, int32_t value)
8✔
34
{
35
    if (name.size() > 16) {
8✔
36
        return ParamServer::Result::ParamNameTooLong;
×
37
    }
38
    _server_component_impl->mavlink_parameter_receiver().provide_server_param_int(name, value);
8✔
39
    return ParamServer::Result::Success;
8✔
40
}
41

42
std::pair<ParamServer::Result, float> ParamServerImpl::retrieve_param_float(std::string name) const
2✔
43
{
44
    const auto result =
2✔
45
        _server_component_impl->mavlink_parameter_receiver().retrieve_server_param_float(name);
2✔
46

47
    if (result.first == MavlinkParameterReceiver::Result::Success) {
2✔
48
        return {ParamServer::Result::Success, result.second};
2✔
49
    } else {
50
        return {ParamServer::Result::NotFound, NAN};
×
51
    }
52
}
53

54
ParamServer::Result ParamServerImpl::provide_param_float(std::string name, float value)
8✔
55
{
56
    if (name.size() > 16) {
8✔
57
        return ParamServer::Result::ParamNameTooLong;
×
58
    }
59
    _server_component_impl->mavlink_parameter_receiver().provide_server_param_float(name, value);
8✔
60
    return ParamServer::Result::Success;
8✔
61
}
62

63
std::pair<ParamServer::Result, std::string>
64
ParamServerImpl::retrieve_param_custom(std::string name) const
2✔
65
{
66
    const auto result =
2✔
67
        _server_component_impl->mavlink_parameter_receiver().retrieve_server_param_custom(name);
4✔
68

69
    if (result.first == MavlinkParameterReceiver::Result::Success) {
2✔
70
        return {ParamServer::Result::Success, result.second};
2✔
71
    } else {
72
        return {ParamServer::Result::NotFound, {}};
×
73
    }
74
}
75

76
ParamServer::Result
77
ParamServerImpl::provide_param_custom(std::string name, const std::string& value)
8✔
78
{
79
    if (name.size() > 16) {
8✔
80
        return ParamServer::Result::ParamNameTooLong;
×
81
    }
82
    _server_component_impl->mavlink_parameter_receiver().provide_server_param_custom(name, value);
8✔
83
    return ParamServer::Result::Success;
8✔
84
}
85

86
ParamServer::AllParams ParamServerImpl::retrieve_all_params() const
2✔
87
{
88
    auto tmp = _server_component_impl->mavlink_parameter_receiver().retrieve_all_server_params();
4✔
89

90
    ParamServer::AllParams res{};
2✔
91

92
    for (auto const& param_pair : tmp) {
6✔
93
        if (param_pair.second.is<float>()) {
4✔
94
            ParamServer::FloatParam tmp_param;
4✔
95
            tmp_param.name = param_pair.first;
2✔
96
            tmp_param.value = param_pair.second.get<float>();
2✔
97
            res.float_params.push_back(tmp_param);
2✔
98
        } else if (param_pair.second.is<int32_t>()) {
2✔
99
            ParamServer::IntParam tmp_param;
4✔
100
            tmp_param.name = param_pair.first;
2✔
101
            tmp_param.value = param_pair.second.get<int32_t>();
2✔
102
            res.int_params.push_back(tmp_param);
2✔
103
        }
104
    }
105

106
    return res;
2✔
107
}
108

109
ParamServer::Result ParamServerImpl::result_from_mavlink_parameter_receiver_result(
×
110
    MavlinkParameterReceiver::Result result)
111
{
112
    switch (result) {
×
113
        case MavlinkParameterReceiver::Result::Success:
×
114
            return ParamServer::Result::Success;
×
115
        case MavlinkParameterReceiver::Result::NotFound:
×
116
            return ParamServer::Result::NotFound;
×
117
        case MavlinkParameterReceiver::Result::ParamNameTooLong:
×
118
            return ParamServer::Result::ParamNameTooLong;
×
119
        case MavlinkParameterReceiver::Result::WrongType:
×
120
            return ParamServer::Result::WrongType;
×
121
        case MavlinkParameterReceiver::Result::ParamValueTooLong:
×
122
            return ParamServer::Result::ParamValueTooLong;
×
123
        default:
×
124
            LogErr() << "Unknown param error";
×
125
            return ParamServer::Result::Unknown;
×
126
    }
127
}
128

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