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

mavlink / MAVSDK / 6568658631

19 Oct 2023 01:31AM UTC coverage: 31.23% (+0.02%) from 31.215%
6568658631

push

github

web-flow
Merge pull request #2155 from mavlink/pr-static-fixes

Threading fixes, MAVLink sequence number cleanup

1386 of 1386 new or added lines in 46 files covered. (100.0%)

7906 of 25315 relevant lines covered (31.23%)

23.54 hits per line

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

0.0
/src/mavsdk/plugins/tracking_server/tracking_server_impl.cpp
1
#include "tracking_server_impl.h"
2
#include "callback_list.tpp"
3
#include "mavlink_address.h"
4
#include <mutex>
5

6
namespace mavsdk {
7

8
template class CallbackList<TrackingServer::TrackPoint>;
9
template class CallbackList<TrackingServer::TrackRectangle>;
10
template class CallbackList<int32_t>;
11

12
TrackingServerImpl::TrackingServerImpl(std::shared_ptr<ServerComponent> server_component) :
×
13
    ServerPluginImplBase(server_component)
×
14
{
15
    // FIXME: use other component ID?
16
    _server_component_impl->register_plugin(this);
×
17
}
×
18

19
TrackingServerImpl::~TrackingServerImpl()
×
20
{
21
    // FIXME: use other component ID?
22
    _server_component_impl->unregister_plugin(this);
×
23
}
×
24

25
void TrackingServerImpl::init()
×
26
{
27
    _server_component_impl->register_mavlink_command_handler(
×
28
        MAV_CMD_CAMERA_TRACK_POINT,
29
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
30
            return process_track_point_command(command);
×
31
        },
32
        this);
33

34
    _server_component_impl->register_mavlink_command_handler(
×
35
        MAV_CMD_CAMERA_TRACK_RECTANGLE,
36
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
37
            return process_track_rectangle_command(command);
×
38
        },
39
        this);
40

41
    _server_component_impl->register_mavlink_command_handler(
×
42
        MAV_CMD_CAMERA_STOP_TRACKING,
43
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
44
            return process_track_off_command(command);
×
45
        },
46
        this);
47
}
×
48

49
void TrackingServerImpl::deinit()
×
50
{
51
    _server_component_impl->unregister_mavlink_command_handler(MAV_CMD_CAMERA_TRACK_POINT, this);
×
52
    _server_component_impl->unregister_mavlink_command_handler(
×
53
        MAV_CMD_CAMERA_TRACK_RECTANGLE, this);
54
    _server_component_impl->unregister_mavlink_command_handler(MAV_CMD_CAMERA_STOP_TRACKING, this);
×
55
}
×
56

57
void TrackingServerImpl::set_tracking_point_status(TrackingServer::TrackPoint tracked_point)
×
58
{
59
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
60
        mavlink_message_t message;
61
        mavlink_msg_camera_tracking_image_status_pack_chan(
×
62
            mavlink_address.system_id,
×
63
            mavlink_address.component_id,
×
64
            channel,
65
            &message,
66
            CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
67
            CAMERA_TRACKING_MODE_POINT,
68
            CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
69
            tracked_point.point_x,
×
70
            tracked_point.point_y,
71
            tracked_point.radius,
72
            0.0f,
73
            0.0f,
74
            0.0f,
75
            0.0f);
76
        return message;
×
77
    });
78
}
×
79

80
void TrackingServerImpl::set_tracking_rectangle_status(
×
81
    TrackingServer::TrackRectangle tracked_rectangle)
82
{
83
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
84
        mavlink_message_t message;
85
        mavlink_msg_camera_tracking_image_status_pack_chan(
×
86
            mavlink_address.system_id,
×
87
            mavlink_address.component_id,
×
88
            channel,
89
            &message,
90
            CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
91
            CAMERA_TRACKING_MODE_RECTANGLE,
92
            CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
93
            0.0f,
94
            0.0f,
95
            0.0f,
96
            tracked_rectangle.top_left_corner_x,
×
97
            tracked_rectangle.top_left_corner_y,
98
            tracked_rectangle.bottom_right_corner_x,
99
            tracked_rectangle.bottom_right_corner_y);
100
        return message;
×
101
    });
102
}
×
103

104
void TrackingServerImpl::set_tracking_off_status()
×
105
{
106
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
107
        mavlink_message_t message;
108
        mavlink_msg_camera_tracking_image_status_pack_chan(
×
109
            mavlink_address.system_id,
×
110
            mavlink_address.component_id,
×
111
            channel,
112
            &message,
113
            CAMERA_TRACKING_STATUS_FLAGS_IDLE,
114
            CAMERA_TRACKING_MODE_NONE,
115
            CAMERA_TRACKING_TARGET_DATA_NONE,
116
            0.0f,
117
            0.0f,
118
            0.0f,
119
            0.0f,
120
            0.0f,
121
            0.0f,
122
            0.0f);
123
        return message;
×
124
    });
125
}
×
126

127
TrackingServer::TrackingPointCommandHandle TrackingServerImpl::subscribe_tracking_point_command(
×
128
    const TrackingServer::TrackingPointCommandCallback& callback)
129
{
130
    std::lock_guard<std::mutex> lock(_mutex);
×
131
    return _tracking_point_callbacks.subscribe(callback);
×
132
}
133

134
void TrackingServerImpl::unsubscribe_tracking_point_command(
×
135
    TrackingServer::TrackingPointCommandHandle handle)
136
{
137
    std::lock_guard<std::mutex> lock(_mutex);
×
138
    _tracking_point_callbacks.unsubscribe(handle);
×
139
}
×
140

141
TrackingServer::TrackingRectangleCommandHandle
142
TrackingServerImpl::subscribe_tracking_rectangle_command(
×
143
    const TrackingServer::TrackingRectangleCommandCallback& callback)
144
{
145
    std::lock_guard<std::mutex> lock(_mutex);
×
146
    return _tracking_rectangle_callbacks.subscribe(callback);
×
147
}
148

149
void TrackingServerImpl::unsubscribe_tracking_rectangle_command(
×
150
    TrackingServer::TrackingRectangleCommandHandle handle)
151
{
152
    std::lock_guard<std::mutex> lock(_mutex);
×
153
    _tracking_rectangle_callbacks.unsubscribe(handle);
×
154
}
×
155

156
TrackingServer::TrackingOffCommandHandle TrackingServerImpl::subscribe_tracking_off_command(
×
157
    const TrackingServer::TrackingOffCommandCallback& callback)
158
{
159
    std::lock_guard<std::mutex> lock(_mutex);
×
160
    return _tracking_off_callbacks.subscribe(callback);
×
161
}
162

163
void TrackingServerImpl::unsubscribe_tracking_off_command(
×
164
    TrackingServer::TrackingOffCommandHandle handle)
165
{
166
    std::lock_guard<std::mutex> lock(_mutex);
×
167
    _tracking_off_callbacks.unsubscribe(handle);
×
168
}
×
169

170
TrackingServer::Result
171
TrackingServerImpl::respond_tracking_point_command(TrackingServer::CommandAnswer command_answer)
×
172
{
173
    std::lock_guard<std::mutex> lock(_mutex);
×
174

175
    return _server_component_impl->queue_message(
×
176
               [&](MavlinkAddress mavlink_address, uint8_t channel) {
×
177
                   mavlink_message_t message;
178
                   mavlink_msg_command_ack_pack_chan(
×
179
                       mavlink_address.system_id,
×
180
                       mavlink_address.component_id,
×
181
                       channel,
182
                       &message,
183
                       MAV_CMD_CAMERA_TRACK_POINT,
184
                       mav_result_from_command_answer(command_answer),
×
185
                       0,
186
                       0,
187
                       _tracking_point_command_sysid,
×
188
                       _tracking_point_command_compid);
×
189
                   return message;
×
190
               }) ?
×
191
               TrackingServer::Result::Success :
192
               TrackingServer::Result::ConnectionError;
×
193
}
194

195
TrackingServer::Result
196
TrackingServerImpl::respond_tracking_rectangle_command(TrackingServer::CommandAnswer command_answer)
×
197
{
198
    std::lock_guard<std::mutex> lock(_mutex);
×
199

200
    return _server_component_impl->queue_message(
×
201
               [&](MavlinkAddress mavlink_address, uint8_t channel) {
×
202
                   mavlink_message_t message;
203
                   mavlink_msg_command_ack_pack_chan(
×
204
                       mavlink_address.system_id,
×
205
                       mavlink_address.component_id,
×
206
                       channel,
207
                       &message,
208
                       MAV_CMD_CAMERA_TRACK_RECTANGLE,
209
                       mav_result_from_command_answer(command_answer),
×
210
                       0,
211
                       0,
212
                       _tracking_rectangle_command_sysid,
×
213
                       _tracking_rectangle_command_compid);
×
214
                   return message;
×
215
               }) ?
×
216
               TrackingServer::Result::Success :
217
               TrackingServer::Result::ConnectionError;
×
218
}
219

220
TrackingServer::Result
221
TrackingServerImpl::respond_tracking_off_command(TrackingServer::CommandAnswer command_answer)
×
222
{
223
    std::lock_guard<std::mutex> lock(_mutex);
×
224

225
    return _server_component_impl->queue_message(
×
226
               [&](MavlinkAddress mavlink_address, uint8_t channel) {
×
227
                   mavlink_message_t message;
228
                   mavlink_msg_command_ack_pack_chan(
×
229
                       mavlink_address.system_id,
×
230
                       mavlink_address.component_id,
×
231
                       channel,
232
                       &message,
233
                       MAV_CMD_CAMERA_STOP_TRACKING,
234
                       mav_result_from_command_answer(command_answer),
×
235
                       0,
236
                       0,
237
                       _tracking_off_command_sysid,
×
238
                       _tracking_off_command_compid);
×
239
                   return message;
×
240
               }) ?
×
241
               TrackingServer::Result::Success :
242
               TrackingServer::Result::ConnectionError;
×
243
}
244

245
std::optional<mavlink_command_ack_t>
246
TrackingServerImpl::process_track_point_command(const MavlinkCommandReceiver::CommandLong& command)
×
247
{
248
    if (!is_command_sender_ok(command)) {
×
249
        LogWarn() << "Incoming track point command is for target sysid "
×
250
                  << int(command.target_system_id) << " instead of "
×
251
                  << int(_server_component_impl->get_own_system_id());
×
252
        return std::nullopt;
×
253
    }
254

255
    TrackingServer::TrackPoint track_point{
×
256
        command.params.param1, command.params.param2, command.params.param3};
×
257

258
    std::lock_guard<std::mutex> lock(_mutex);
×
259
    _tracking_point_command_sysid = command.origin_system_id;
×
260
    _tracking_point_command_compid = command.origin_component_id;
×
261

262
    _tracking_point_callbacks.queue(track_point, [this](const auto& func) {
×
263
        _server_component_impl->call_user_callback(func);
×
264
    });
×
265

266
    // We don't send an ack but leave that to the user.
267
    return std::nullopt;
×
268
}
269

270
std::optional<mavlink_command_ack_t> TrackingServerImpl::process_track_rectangle_command(
×
271
    const MavlinkCommandReceiver::CommandLong& command)
272
{
273
    if (!is_command_sender_ok(command)) {
×
274
        LogWarn() << "Incoming track rectangle command is for target sysid "
×
275
                  << int(command.target_system_id) << " instead of "
×
276
                  << int(_server_component_impl->get_own_system_id());
×
277
        return std::nullopt;
×
278
    }
279

280
    TrackingServer::TrackRectangle track_rectangle{
×
281
        command.params.param1, command.params.param2, command.params.param3, command.params.param4};
×
282

283
    std::lock_guard<std::mutex> lock(_mutex);
×
284
    _tracking_rectangle_command_sysid = command.origin_system_id;
×
285
    _tracking_rectangle_command_compid = command.origin_component_id;
×
286

287
    _tracking_rectangle_callbacks.queue(track_rectangle, [this](const auto& func) {
×
288
        _server_component_impl->call_user_callback(func);
×
289
    });
×
290

291
    // We don't send an ack but leave that to the user.
292
    return std::nullopt;
×
293
}
294

295
std::optional<mavlink_command_ack_t>
296
TrackingServerImpl::process_track_off_command(const MavlinkCommandReceiver::CommandLong& command)
×
297
{
298
    if (!is_command_sender_ok(command)) {
×
299
        LogWarn() << "Incoming track off command is for target sysid "
×
300
                  << int(command.target_system_id) << " instead of "
×
301
                  << int(_server_component_impl->get_own_system_id());
×
302
        return std::nullopt;
×
303
    }
304

305
    std::lock_guard<std::mutex> lock(_mutex);
×
306
    _tracking_off_command_sysid = command.origin_system_id;
×
307
    _tracking_off_command_compid = command.origin_component_id;
×
308

309
    _tracking_off_callbacks.queue(
×
310
        0, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
311

312
    // We don't send an ack but leave that to the user.
313
    return std::nullopt;
×
314
}
315

316
bool TrackingServerImpl::is_command_sender_ok(const MavlinkCommandReceiver::CommandLong& command)
×
317
{
318
    if (command.target_system_id != 0 &&
×
319
        command.target_system_id != _server_component_impl->get_own_system_id()) {
×
320
        return false;
×
321
    } else {
322
        return true;
×
323
    }
324
}
325

326
MAV_RESULT
327
TrackingServerImpl::mav_result_from_command_answer(TrackingServer::CommandAnswer command_answer)
×
328
{
329
    switch (command_answer) {
×
330
        case TrackingServer::CommandAnswer::Accepted:
×
331
            return MAV_RESULT_ACCEPTED;
×
332
        case TrackingServer::CommandAnswer::TemporarilyRejected:
×
333
            return MAV_RESULT_TEMPORARILY_REJECTED;
×
334
        case TrackingServer::CommandAnswer::Denied:
×
335
            return MAV_RESULT_DENIED;
×
336
        case TrackingServer::CommandAnswer::Unsupported:
×
337
            return MAV_RESULT_UNSUPPORTED;
×
338
        case TrackingServer::CommandAnswer::Failed:
×
339
            return MAV_RESULT_FAILED;
×
340
    }
341

342
    LogErr() << "Unknown CommandAnswer";
×
343
    return MAV_RESULT_FAILED;
×
344
}
345

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