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

mavlink / MAVSDK / 19124558934

06 Nov 2025 04:13AM UTC coverage: 48.329% (+0.2%) from 48.156%
19124558934

push

github

web-flow
Merge pull request #2682 from mavlink/pr-raw-bytes

core: add raw connection

154 of 169 new or added lines in 6 files covered. (91.12%)

381 existing lines in 8 files now uncovered.

17643 of 36506 relevant lines covered (48.33%)

469.45 hits per line

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

56.35
/src/mavsdk/plugins/param/param_impl.cpp
1
#include <functional>
2
#include "param_impl.h"
3
#include "system.h"
4
#include "unused.h"
5

6
namespace mavsdk {
7

8
ParamImpl::ParamImpl(System& system) : PluginImplBase(system)
×
9
{
10
    _system_impl->register_plugin(this);
×
11
}
×
12

13
ParamImpl::ParamImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
8✔
14
{
15
    _system_impl->register_plugin(this);
8✔
16
}
8✔
17

18
ParamImpl::~ParamImpl()
16✔
19
{
20
    _system_impl->unregister_plugin(this);
8✔
21
}
16✔
22

23
void ParamImpl::init() {}
8✔
24

25
void ParamImpl::deinit() {}
8✔
26

27
void ParamImpl::enable() {}
8✔
28

29
void ParamImpl::disable() {}
8✔
30

31
std::pair<Param::Result, int32_t> ParamImpl::get_param_int(const std::string& name)
5✔
32
{
33
    std::pair<MavlinkParameterClient::Result, int32_t> result = _system_impl->get_param_int(
10✔
34
        name, _component_id, _protocol_version == Param::ProtocolVersion::Ext);
5✔
35
    return std::make_pair<>(
5✔
36
        result_from_mavlink_parameter_client_result(result.first), result.second);
5✔
37
}
38

39
Param::Result ParamImpl::set_param_int(const std::string& name, int32_t value)
2✔
40
{
41
    MavlinkParameterClient::Result result = _system_impl->set_param_int(
4✔
42
        name, value, _component_id, _protocol_version == Param::ProtocolVersion::Ext);
2✔
43
    return result_from_mavlink_parameter_client_result(result);
2✔
44
}
45

46
std::pair<Param::Result, float> ParamImpl::get_param_float(const std::string& name)
5✔
47
{
48
    std::pair<MavlinkParameterClient::Result, float> result = _system_impl->get_param_float(
10✔
49
        name, _component_id, _protocol_version == Param::ProtocolVersion::Ext);
5✔
50
    return std::make_pair<>(
5✔
51
        result_from_mavlink_parameter_client_result(result.first), result.second);
5✔
52
}
53

54
Param::Result ParamImpl::set_param_float(const std::string& name, float value)
2✔
55
{
56
    MavlinkParameterClient::Result result = _system_impl->set_param_float(
4✔
57
        name, value, _component_id, _protocol_version == Param::ProtocolVersion::Ext);
2✔
58
    return result_from_mavlink_parameter_client_result(result);
2✔
59
}
60

61
std::pair<Param::Result, std::string> ParamImpl::get_param_custom(const std::string& name)
4✔
62
{
63
    auto result = _system_impl->get_param_custom(name, _component_id);
4✔
64
    return std::make_pair<>(
65
        result_from_mavlink_parameter_client_result(result.first), result.second);
4✔
66
}
4✔
67

68
Param::Result ParamImpl::set_param_custom(const std::string& name, const std::string& value)
2✔
69
{
70
    auto result = _system_impl->set_param_custom(name, value, _component_id);
2✔
71
    return result_from_mavlink_parameter_client_result(result);
2✔
72
}
73

74
Param::AllParams ParamImpl::get_all_params()
4✔
75
{
76
    auto tmp = _system_impl->get_all_params(
4✔
77
        _component_id, _protocol_version == Param::ProtocolVersion::Ext);
4✔
78

79
    if (tmp.first != MavlinkParameterClient::Result::Success) {
4✔
80
        return {};
×
81
    }
82

83
    Param::AllParams res{};
4✔
84
    for (auto const& param_pair : tmp.second) {
34✔
85
        if (param_pair.second.is<float>()) {
30✔
86
            Param::FloatParam tmp_param;
12✔
87
            tmp_param.name = param_pair.first;
12✔
88
            tmp_param.value = param_pair.second.get<float>();
12✔
89
            res.float_params.push_back(tmp_param);
12✔
90
        } else if (param_pair.second.is<int32_t>()) {
30✔
91
            Param::IntParam tmp_param;
12✔
92
            tmp_param.name = param_pair.first;
12✔
93
            tmp_param.value = param_pair.second.get<int32_t>();
12✔
94
            res.int_params.push_back(tmp_param);
12✔
95
        } else if (param_pair.second.is<int16_t>()) {
18✔
96
            Param::IntParam tmp_param;
×
97
            tmp_param.name = param_pair.first;
×
98
            tmp_param.value = param_pair.second.get<int16_t>();
×
99
            res.int_params.push_back(tmp_param);
×
100
        } else if (param_pair.second.is<int8_t>()) {
6✔
101
            Param::IntParam tmp_param;
×
102
            tmp_param.name = param_pair.first;
×
103
            tmp_param.value = param_pair.second.get<int8_t>();
×
104
            res.int_params.push_back(tmp_param);
×
105
        } else if (param_pair.second.is<std::string>()) {
6✔
106
            Param::CustomParam tmp_param;
6✔
107
            tmp_param.name = param_pair.first;
6✔
108
            tmp_param.value = param_pair.second.get<std::string>();
6✔
109
            res.custom_params.push_back(tmp_param);
6✔
110
        }
6✔
111
    }
112

113
    return res;
4✔
114
}
4✔
115

116
Param::Result
117
ParamImpl::select_component(int32_t component_id, Param::ProtocolVersion protocol_version)
6✔
118
{
119
    _component_id = component_id;
6✔
120
    _protocol_version = protocol_version;
6✔
121
    return Param::Result::Unknown;
6✔
122
}
123

124
Param::Result
125
ParamImpl::result_from_mavlink_parameter_client_result(MavlinkParameterClient::Result result)
20✔
126
{
127
    switch (result) {
20✔
128
        case MavlinkParameterClient::Result::Success:
18✔
129
            return Param::Result::Success;
18✔
UNCOV
130
        case MavlinkParameterClient::Result::Timeout:
×
UNCOV
131
            return Param::Result::Timeout;
×
132
        case MavlinkParameterClient::Result::ConnectionError:
×
133
            return Param::Result::ConnectionError;
×
134
        case MavlinkParameterClient::Result::WrongType:
×
135
            return Param::Result::WrongType;
×
136
        case MavlinkParameterClient::Result::ParamNameTooLong:
×
137
            return Param::Result::ParamNameTooLong;
×
138
        case MavlinkParameterClient::Result::NotFound:
×
139
            LogWarn() << "NotFound";
×
140
            return Param::Result::Unknown; // TODO fix - no corresponding proto Result yet
×
141
        case MavlinkParameterClient::Result::ValueUnsupported:
×
142
            LogWarn() << "ValueUnsupported";
×
143
            return Param::Result::Unknown; // TODO fix - no corresponding proto Result yet
×
144
        case MavlinkParameterClient::Result::Failed:
×
145
            return Param::Result::Failed;
×
146
        case MavlinkParameterClient::Result::ParamValueTooLong:
×
147
            return Param::Result::ParamValueTooLong;
×
148
        case MavlinkParameterClient::Result::StringTypeUnsupported:
×
149
            LogWarn() << "StringTypeUnsupported";
×
150
            return Param::Result::Unknown; // TODO fix - no corresponding proto Result yet
×
151
        case MavlinkParameterClient::Result::InconsistentData:
×
152
            LogWarn() << "InconsistentData";
×
153
            return Param::Result::Unknown; // TODO fix - no corresponding proto Result yet
×
154
        case MavlinkParameterClient::Result::UnknownError:
×
155
            return Param::Result::Unknown;
×
156
        // New PARAM_ERROR codes
157
        case MavlinkParameterClient::Result::DoesNotExist:
2✔
158
            return Param::Result::DoesNotExist;
2✔
159
        case MavlinkParameterClient::Result::ValueOutOfRange:
×
160
            return Param::Result::ValueOutOfRange;
×
UNCOV
161
        case MavlinkParameterClient::Result::PermissionDenied:
×
UNCOV
162
            return Param::Result::PermissionDenied;
×
UNCOV
163
        case MavlinkParameterClient::Result::ComponentNotFound:
×
UNCOV
164
            return Param::Result::ComponentNotFound;
×
UNCOV
165
        case MavlinkParameterClient::Result::ReadOnly:
×
UNCOV
166
            return Param::Result::ReadOnly;
×
UNCOV
167
        case MavlinkParameterClient::Result::TypeUnsupported:
×
UNCOV
168
            return Param::Result::TypeUnsupported;
×
UNCOV
169
        case MavlinkParameterClient::Result::TypeMismatch:
×
UNCOV
170
            return Param::Result::TypeMismatch;
×
UNCOV
171
        case MavlinkParameterClient::Result::ReadFail:
×
UNCOV
172
            return Param::Result::ReadFail;
×
UNCOV
173
        default:
×
UNCOV
174
            LogErr() << "Unknown param error" << (int)result;
×
UNCOV
175
            return Param::Result::Unknown;
×
176
    }
177
}
178

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