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

mavlink / MAVSDK / 19917394289

04 Dec 2025 04:11AM UTC coverage: 47.954%. First build
19917394289

Pull #2728

github

web-flow
Merge 9e6a433c4 into de36b0d7d
Pull Request #2728: log_streaming: add ArduPilot support

0 of 425 new or added lines in 6 files covered. (0.0%)

17635 of 36775 relevant lines covered (47.95%)

464.38 hits per line

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

0.0
/src/mavsdk/plugins/log_streaming/log_streaming_backend_ardupilot.cpp
1
#include "log_streaming_backend_ardupilot.h"
2

3
// ArduPilot uses REMOTE_LOG_DATA_BLOCK (ID 184) for real-time log streaming.
4
// This is different from PX4's LOGGING_DATA protocol.
5
//
6
// Protocol:
7
// - GCS sends REMOTE_LOG_BLOCK_STATUS with seqno = MAV_REMOTE_LOG_DATA_BLOCK_START to start
8
// - GCS sends REMOTE_LOG_BLOCK_STATUS with seqno = MAV_REMOTE_LOG_DATA_BLOCK_STOP to stop
9
// - Autopilot streams REMOTE_LOG_DATA_BLOCK messages with 200 bytes of DataFlash data
10
// - GCS should ACK each block with REMOTE_LOG_BLOCK_STATUS
11

12
namespace mavsdk {
13

NEW
14
void LogStreamingBackendArdupilot::init(SystemImpl* system_impl)
×
15
{
NEW
16
    _system_impl = system_impl;
×
17

NEW
18
    _system_impl->register_mavlink_message_handler(
×
19
        MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK,
NEW
20
        [this](const mavlink_message_t& message) { process_remote_log_data_block(message); },
×
21
        this);
NEW
22
}
×
23

NEW
24
void LogStreamingBackendArdupilot::deinit()
×
25
{
NEW
26
    auto is_active = [this]() {
×
NEW
27
        std::lock_guard<std::mutex> lock(_mutex);
×
NEW
28
        return _active;
×
NEW
29
    }();
×
30

NEW
31
    if (is_active) {
×
32
        // We try to stop log streaming before we leave but without waiting for a result.
NEW
33
        stop_log_streaming_async(nullptr);
×
34
    }
35

NEW
36
    if (_system_impl) {
×
NEW
37
        _system_impl->unregister_all_mavlink_message_handlers(this);
×
38
    }
NEW
39
}
×
40

NEW
41
void LogStreamingBackendArdupilot::set_data_callback(DataCallback callback)
×
42
{
NEW
43
    std::lock_guard<std::mutex> lock(_mutex);
×
NEW
44
    _data_callback = std::move(callback);
×
NEW
45
}
×
46

NEW
47
void LogStreamingBackendArdupilot::set_debugging(bool debugging)
×
48
{
NEW
49
    _debugging = debugging;
×
NEW
50
}
×
51

NEW
52
void LogStreamingBackendArdupilot::start_log_streaming_async(
×
53
    const LogStreaming::ResultCallback& callback)
54
{
55
    {
NEW
56
        std::lock_guard<std::mutex> lock(_mutex);
×
NEW
57
        _active = true;
×
NEW
58
        _first_block_received = false;
×
NEW
59
        _last_seqno = 0;
×
NEW
60
    }
×
61

62
    // Send START command via REMOTE_LOG_BLOCK_STATUS
NEW
63
    send_remote_log_block_status(MAV_REMOTE_LOG_DATA_BLOCK_START, MAV_REMOTE_LOG_DATA_BLOCK_ACK);
×
64

NEW
65
    if (_debugging) {
×
NEW
66
        LogDebug() << "Sent REMOTE_LOG_BLOCK_STATUS with seqno=START to "
×
NEW
67
                   << static_cast<int>(_system_impl->get_system_id()) << "/"
×
NEW
68
                   << static_cast<int>(_system_impl->get_autopilot_id());
×
69
    }
70

71
    // ArduPilot doesn't acknowledge the start command,
72
    // so we assume success immediately
NEW
73
    if (callback) {
×
NEW
74
        _system_impl->call_user_callback([callback]() { callback(LogStreaming::Result::Success); });
×
75
    }
NEW
76
}
×
77

NEW
78
void LogStreamingBackendArdupilot::stop_log_streaming_async(
×
79
    const LogStreaming::ResultCallback& callback)
80
{
81
    // Send STOP command via REMOTE_LOG_BLOCK_STATUS
NEW
82
    send_remote_log_block_status(MAV_REMOTE_LOG_DATA_BLOCK_STOP, MAV_REMOTE_LOG_DATA_BLOCK_ACK);
×
83

NEW
84
    if (_debugging) {
×
NEW
85
        LogDebug() << "Sent REMOTE_LOG_DATA_BLOCK_STOP";
×
86
    }
87

88
    {
NEW
89
        std::lock_guard<std::mutex> lock(_mutex);
×
NEW
90
        _active = false;
×
NEW
91
    }
×
92

93
    // ArduPilot doesn't acknowledge the stop command,
94
    // so we assume success immediately
NEW
95
    if (callback) {
×
NEW
96
        _system_impl->call_user_callback([callback]() { callback(LogStreaming::Result::Success); });
×
97
    }
NEW
98
}
×
99

NEW
100
void LogStreamingBackendArdupilot::send_remote_log_block_status(uint32_t seqno, uint8_t status)
×
101
{
NEW
102
    auto target_sysid = _system_impl->get_system_id();
×
NEW
103
    auto target_compid = _system_impl->get_autopilot_id();
×
104

NEW
105
    if (_debugging) {
×
NEW
106
        LogDebug() << "Sending REMOTE_LOG_BLOCK_STATUS: seqno=" << seqno
×
NEW
107
                   << " status=" << static_cast<int>(status)
×
NEW
108
                   << " target=" << static_cast<int>(target_sysid) << "/"
×
NEW
109
                   << static_cast<int>(target_compid);
×
110
    }
111

NEW
112
    _system_impl->queue_message([target_sysid, target_compid, seqno, status](
×
NEW
113
                                    MavlinkAddress mavlink_address, uint8_t channel) {
×
114
        mavlink_message_t message;
NEW
115
        mavlink_msg_remote_log_block_status_pack_chan(
×
NEW
116
            mavlink_address.system_id,
×
NEW
117
            mavlink_address.component_id,
×
118
            channel,
119
            &message,
120
            target_sysid,
121
            target_compid,
122
            seqno,
123
            status);
NEW
124
        return message;
×
125
    });
NEW
126
}
×
127

NEW
128
void LogStreamingBackendArdupilot::process_remote_log_data_block(const mavlink_message_t& message)
×
129
{
NEW
130
    if (_debugging) {
×
NEW
131
        LogDebug() << "Received REMOTE_LOG_DATA_BLOCK from " << static_cast<int>(message.sysid)
×
NEW
132
                   << "/" << static_cast<int>(message.compid);
×
133
    }
134

NEW
135
    std::lock_guard<std::mutex> lock(_mutex);
×
136

NEW
137
    if (!_active) {
×
NEW
138
        if (_debugging) {
×
NEW
139
            LogDebug() << "Ignoring remote log data block because we're not active";
×
140
        }
NEW
141
        return;
×
142
    }
143

144
    mavlink_remote_log_data_block_t block;
NEW
145
    mavlink_msg_remote_log_data_block_decode(&message, &block);
×
146

147
    // Check if this message is targeted at us
NEW
148
    if (block.target_system != _system_impl->get_own_system_id() ||
×
NEW
149
        block.target_component != _system_impl->get_own_component_id()) {
×
NEW
150
        if (_debugging) {
×
NEW
151
            LogDebug() << "Remote log data block with wrong target "
×
NEW
152
                       << std::to_string(block.target_system) << '/'
×
NEW
153
                       << std::to_string(block.target_component) << " instead of "
×
NEW
154
                       << std::to_string(_system_impl->get_own_system_id()) << '/'
×
NEW
155
                       << std::to_string(_system_impl->get_own_component_id());
×
156
        }
NEW
157
        return;
×
158
    }
159

NEW
160
    if (_debugging) {
×
NEW
161
        LogDebug() << "Received remote log data block with seqno: " << block.seqno;
×
162
    }
163

164
    // Check for dropped blocks
NEW
165
    if (_first_block_received) {
×
NEW
166
        uint32_t expected_seqno = _last_seqno + 1;
×
NEW
167
        if (block.seqno != expected_seqno) {
×
NEW
168
            uint32_t dropped = block.seqno - expected_seqno;
×
NEW
169
            if (_debugging) {
×
NEW
170
                LogDebug() << "Dropped " << dropped << " blocks (expected " << expected_seqno
×
NEW
171
                           << ", got " << block.seqno << ")";
×
172
            }
173
            // We could potentially NACK the missing blocks to request retransmission,
174
            // but for now we just note the drop and continue
175
        }
176
    } else {
NEW
177
        _first_block_received = true;
×
178
    }
NEW
179
    _last_seqno = block.seqno;
×
180

181
    // Send ACK for this block
NEW
182
    send_remote_log_block_status(block.seqno, MAV_REMOTE_LOG_DATA_BLOCK_ACK);
×
183

184
    // The data block is always 200 bytes (fixed size in the message definition)
NEW
185
    std::vector<uint8_t> data(block.data, block.data + sizeof(block.data));
×
186

187
    // Pass data to the user via the callback
NEW
188
    if (_data_callback) {
×
NEW
189
        _system_impl->call_user_callback([this, data]() { _data_callback(data); });
×
190
    }
NEW
191
}
×
192

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

© 2026 Coveralls, Inc