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

mavlink / MAVSDK / 11767930807

10 Nov 2024 07:33PM UTC coverage: 38.608% (+0.7%) from 37.921%
11767930807

push

github

web-flow
Merge pull request #2394 from mavlink/pr-consolidate-ci

Consolidate CI

12030 of 31159 relevant lines covered (38.61%)

243.33 hits per line

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

0.0
/src/mavsdk/plugins/info/info_impl.cpp
1
#include <cstring>
2
#include <functional>
3
#include <future>
4
#include <numeric>
5
#include "info_impl.h"
6
#include "system.h"
7
#include "callback_list.tpp"
8

9
namespace mavsdk {
10

11
template class CallbackList<Info::FlightInfo>;
12

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

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

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

28
void InfoImpl::init()
×
29
{
30
    _system_impl->register_mavlink_message_handler(
×
31
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
32
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
×
33
        this);
34

35
    _system_impl->register_mavlink_message_handler(
×
36
        MAVLINK_MSG_ID_FLIGHT_INFORMATION,
37
        [this](const mavlink_message_t& message) { process_flight_information(message); },
×
38
        this);
39

40
    _system_impl->register_mavlink_message_handler(
×
41
        MAVLINK_MSG_ID_ATTITUDE,
42
        [this](const mavlink_message_t& message) { process_attitude(message); },
×
43
        this);
44
}
×
45

46
void InfoImpl::deinit()
×
47
{
48
    _system_impl->unregister_all_mavlink_message_handlers(this);
×
49
}
×
50

51
void InfoImpl::enable()
×
52
{
53
    // We're going to retry until we have the version.
54
    _call_every_cookie = _system_impl->add_call_every(
×
55
        [this]() { _system_impl->send_autopilot_version_request(); }, 2.0f);
×
56

57
    if (!_flight_info_subscriptions.empty()) {
×
58
        // We're hoping to get flight information regularly to update flight time.
59
        _system_impl->set_msg_rate_async(MAVLINK_MSG_ID_FLIGHT_INFORMATION, 1.0, nullptr);
×
60
    }
61
}
×
62

63
void InfoImpl::disable()
×
64
{
65
    _system_impl->remove_call_every(_call_every_cookie);
×
66

67
    std::lock_guard<std::mutex> lock(_mutex);
×
68
    _identification_received = false;
×
69
}
×
70

71
void InfoImpl::process_autopilot_version(const mavlink_message_t& message)
×
72
{
73
    _system_impl->remove_call_every(_call_every_cookie);
×
74

75
    std::lock_guard<std::mutex> lock(_mutex);
×
76

77
    mavlink_autopilot_version_t autopilot_version;
×
78
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
×
79

80
    _version.flight_sw_major = (autopilot_version.flight_sw_version >> (8 * 3)) & 0xFF;
×
81
    _version.flight_sw_minor = (autopilot_version.flight_sw_version >> (8 * 2)) & 0xFF;
×
82
    _version.flight_sw_patch = (autopilot_version.flight_sw_version >> (8 * 1)) & 0xFF;
×
83
    _version.flight_sw_version_type =
×
84
        get_flight_software_version_type(static_cast<FIRMWARE_VERSION_TYPE>(
×
85
            (autopilot_version.flight_sw_version >> (8 * 0)) & 0xFF));
×
86

87
    // first three bytes of flight_custom_version (little endian) describe vendor version
88
    _version.flight_sw_git_hash = swap_and_translate_binary_to_str(
×
89
        autopilot_version.flight_custom_version + 3,
90
        sizeof(autopilot_version.flight_custom_version) - 3);
×
91

92
    _version.flight_sw_vendor_major = autopilot_version.flight_custom_version[2];
×
93
    _version.flight_sw_vendor_minor = autopilot_version.flight_custom_version[1];
×
94
    _version.flight_sw_vendor_patch = autopilot_version.flight_custom_version[0];
×
95

96
    _version.os_sw_major = (autopilot_version.os_sw_version >> (8 * 3)) & 0xFF;
×
97
    _version.os_sw_minor = (autopilot_version.os_sw_version >> (8 * 2)) & 0xFF;
×
98
    _version.os_sw_patch = (autopilot_version.os_sw_version >> (8 * 1)) & 0xFF;
×
99

100
    _version.os_sw_git_hash = swap_and_translate_binary_to_str(
×
101
        autopilot_version.os_custom_version, sizeof(autopilot_version.os_custom_version));
×
102

103
    _product.vendor_id = autopilot_version.vendor_id;
×
104
    _product.vendor_name = vendor_id_str(autopilot_version.vendor_id);
×
105

106
    _product.product_id = autopilot_version.product_id;
×
107
    _product.product_name = product_id_str(autopilot_version.product_id);
×
108

109
    _identification.hardware_uid =
×
110
        translate_binary_to_str(autopilot_version.uid2, sizeof(autopilot_version.uid2));
×
111

112
    _identification.legacy_uid = autopilot_version.uid;
×
113

114
    _identification_received = true;
×
115
}
×
116

117
Info::Version::FlightSoftwareVersionType
118
InfoImpl::get_flight_software_version_type(FIRMWARE_VERSION_TYPE firmwareVersionType)
×
119
{
120
    switch (firmwareVersionType) {
×
121
        case FIRMWARE_VERSION_TYPE_DEV:
×
122
            return Info::Version::FlightSoftwareVersionType::Dev;
×
123

124
        case FIRMWARE_VERSION_TYPE_ALPHA:
×
125
            return Info::Version::FlightSoftwareVersionType::Alpha;
×
126

127
        case FIRMWARE_VERSION_TYPE_BETA:
×
128
            return Info::Version::FlightSoftwareVersionType::Beta;
×
129

130
        case FIRMWARE_VERSION_TYPE_RC:
×
131
            return Info::Version::FlightSoftwareVersionType::Rc;
×
132

133
        case FIRMWARE_VERSION_TYPE_OFFICIAL:
×
134
            return Info::Version::FlightSoftwareVersionType::Release;
×
135

136
        default:
×
137
            return Info::Version::FlightSoftwareVersionType::Unknown;
×
138
    }
139
}
140

141
void InfoImpl::process_flight_information(const mavlink_message_t& message)
×
142
{
143
    std::lock_guard<std::mutex> lock(_mutex);
×
144

145
    mavlink_flight_information_t flight_information;
×
146
    mavlink_msg_flight_information_decode(&message, &flight_information);
×
147

148
    _flight_info.time_boot_ms = flight_information.time_boot_ms;
×
149
    _flight_info.flight_uid = flight_information.flight_uuid;
×
150
    // The fields are called UTC but are actually since boot
151
    const auto arming_time_ms = flight_information.arming_time_utc / 1000;
×
152
    const auto takeoff_time_ms = flight_information.takeoff_time_utc / 1000;
×
153

154
    if (arming_time_ms > 0 && arming_time_ms < flight_information.time_boot_ms) {
×
155
        _flight_info.duration_since_arming_ms = flight_information.time_boot_ms - arming_time_ms;
×
156
    } else {
157
        _flight_info.duration_since_arming_ms = 0;
×
158
    }
159

160
    if (takeoff_time_ms > 0 && takeoff_time_ms < flight_information.time_boot_ms) {
×
161
        _flight_info.duration_since_takeoff_ms = flight_information.time_boot_ms - takeoff_time_ms;
×
162
    } else {
163
        _flight_info.duration_since_takeoff_ms = 0;
×
164
    }
165

166
    _flight_info_subscriptions.queue(
×
167
        _flight_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
168
}
×
169

170
std::string InfoImpl::swap_and_translate_binary_to_str(uint8_t* binary, unsigned binary_len)
×
171
{
172
    std::string str(binary_len * 2, '0');
×
173

174
    for (unsigned i = 0; i < binary_len; ++i) {
×
175
        // One hex number occupies 2 chars.
176
        // The binary is in little endian, therefore we need to swap the bytes for us to read.
177
        snprintf(&str[i * 2], str.length() - i * 2, "%02x", binary[binary_len - 1 - i]);
×
178
    }
179

180
    return str;
×
181
}
182

183
std::string InfoImpl::translate_binary_to_str(uint8_t* binary, unsigned binary_len)
×
184
{
185
    std::string str(binary_len * 2 + 1, '0');
×
186

187
    for (unsigned i = 0; i < binary_len; ++i) {
×
188
        // One hex number occupies 2 chars.
189
        snprintf(&str[i * 2], str.length() - i * 2, "%02x", binary[i]);
×
190
    }
191

192
    return str;
×
193
}
194

195
std::pair<Info::Result, Info::Identification> InfoImpl::get_identification() const
×
196
{
197
    wait_for_identification();
×
198

199
    std::lock_guard<std::mutex> lock(_mutex);
×
200
    return std::make_pair<>(
201
        (_identification_received ? Info::Result::Success :
×
202
                                    Info::Result::InformationNotReceivedYet),
203
        _identification);
×
204
}
×
205

206
std::pair<Info::Result, Info::Version> InfoImpl::get_version() const
×
207
{
208
    wait_for_identification();
×
209

210
    std::lock_guard<std::mutex> lock(_mutex);
×
211

212
    return std::make_pair<>(
213
        (_identification_received ? Info::Result::Success :
×
214
                                    Info::Result::InformationNotReceivedYet),
215
        _version);
×
216
}
×
217

218
std::pair<Info::Result, Info::Product> InfoImpl::get_product() const
×
219
{
220
    wait_for_identification();
×
221
    std::lock_guard<std::mutex> lock(_mutex);
×
222

223
    return std::make_pair<>(
224
        (_identification_received ? Info::Result::Success :
×
225
                                    Info::Result::InformationNotReceivedYet),
226
        _product);
×
227
}
×
228

229
std::pair<Info::Result, Info::FlightInfo> InfoImpl::get_flight_information()
×
230
{
231
    std::promise<std::pair<Info::Result, Info::FlightInfo>> prom;
×
232
    auto fut = prom.get_future();
×
233
    _system_impl->mavlink_request_message().request(
×
234
        MAVLINK_MSG_ID_FLIGHT_INFORMATION,
235
        MAV_COMP_ID_AUTOPILOT1,
236
        [&](MavlinkCommandSender::Result result, const mavlink_message_t& message) {
×
237
            if (result == MavlinkCommandSender::Result::Success) {
×
238
                // This call might happen twice but that's ok.
239
                process_flight_information(message);
×
240
                prom.set_value({Info::Result::Success, _flight_info});
×
241
            } else {
242
                prom.set_value({Info::Result::InformationNotReceivedYet, Info::FlightInfo{}});
×
243
            }
244
        });
×
245
    return fut.get();
×
246
}
×
247

248
const std::string InfoImpl::vendor_id_str(uint16_t vendor_id)
×
249
{
250
    switch (vendor_id) {
×
251
        case 0x26ac:
×
252
            return "3D Robotics Inc.";
×
253
        default:
×
254
            return "undefined";
×
255
    }
256
}
257

258
const std::string InfoImpl::product_id_str(uint16_t product_id)
×
259
{
260
    switch (product_id) {
×
261
        case 0x0010:
×
262
            return "H520";
×
263
        default:
×
264
            return "undefined";
×
265
    }
266
}
267

268
void InfoImpl::process_attitude(const mavlink_message_t& message)
×
269
{
270
    // We use the attitude message to estimate the lockstep speed factor
271
    // because it's common to be sent, arrives at high rate, and contains
272
    // the timestamp field.
273
    mavlink_attitude_t attitude;
×
274
    mavlink_msg_attitude_decode(&message, &attitude);
×
275

276
    std::lock_guard<std::mutex> lock(_mutex);
×
277

278
    if (_last_time_boot_ms != 0) {
×
279
        _speed_factor_measurements.push(SpeedFactorMeasurement{
×
280
            static_cast<double>(attitude.time_boot_ms - _last_time_boot_ms) * 1e-3,
×
281
            _time.elapsed_since_s(_last_time_attitude_arrived)});
×
282
    }
283

284
    _last_time_boot_ms = attitude.time_boot_ms;
×
285
    _last_time_attitude_arrived = _time.steady_time();
×
286
}
×
287

288
std::pair<Info::Result, double> InfoImpl::get_speed_factor() const
×
289
{
290
    std::lock_guard<std::mutex> lock(_mutex);
×
291

292
    if (_speed_factor_measurements.size() == 0) {
×
293
        return std::make_pair<>(Info::Result::InformationNotReceivedYet, NAN);
×
294
    }
295

296
    const auto sum = std::accumulate(
×
297
        _speed_factor_measurements.begin(),
298
        _speed_factor_measurements.end(),
299
        SpeedFactorMeasurement{},
300
        [](SpeedFactorMeasurement a, SpeedFactorMeasurement b) { return a + b; });
×
301

302
    const double speed_factor = sum.simulated_duration_s / sum.real_time_s;
×
303

304
    return std::make_pair<>(Info::Result::Success, speed_factor);
×
305
}
×
306

307
void InfoImpl::wait_for_identification() const
×
308
{
309
    // Wait 0.5 seconds max
310
    for (unsigned i = 0; i < 50; ++i) {
×
311
        {
312
            std::lock_guard<std::mutex> lock(_mutex);
×
313
            if (_identification_received) {
×
314
                break;
×
315
            }
316
        }
×
317
        std::this_thread::sleep_for(std::chrono::milliseconds(10));
×
318
    }
319
}
×
320

321
Info::FlightInformationHandle
322
InfoImpl::subscribe_flight_information(const Info::FlightInformationCallback& callback)
×
323
{
324
    // Make sure we get the message regularly.
325
    _system_impl->set_msg_rate_async(MAVLINK_MSG_ID_FLIGHT_INFORMATION, 1.0, nullptr);
×
326

327
    std::lock_guard<std::mutex> lock(_mutex);
×
328

329
    return _flight_info_subscriptions.subscribe(callback);
×
330
}
×
331

332
void InfoImpl::unsubscribe_flight_information(Info::FlightInformationHandle handle)
×
333
{
334
    // Reset message to default
335
    _system_impl->set_msg_rate_async(MAVLINK_MSG_ID_FLIGHT_INFORMATION, 0.0, nullptr);
×
336

337
    std::lock_guard<std::mutex> lock(_mutex);
×
338

339
    _flight_info_subscriptions.unsubscribe(handle);
×
340
}
×
341

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