forked from mavlink/mavlink-camera-manager
-
Notifications
You must be signed in to change notification settings - Fork 0
/
mavlink_camera.rs
651 lines (572 loc) · 26.7 KB
/
mavlink_camera.rs
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
use std::sync::Arc;
use crate::{
cli, mavlink::mavlink_camera_component::MavlinkCameraComponent,
network::utils::get_visible_qgc_address, video::types::VideoSourceType,
video_stream::types::VideoAndStreamInformation,
};
use anyhow::{anyhow, Context, Result};
use mavlink::{common::MavMessage, MavHeader};
use tokio::sync::broadcast;
use tracing::*;
use url::Url;
use super::manager::Message;
use super::utils::*;
#[derive(Debug)]
pub struct MavlinkCamera {
inner: Arc<MavlinkCameraInner>,
heartbeat_handle: Option<tokio::task::JoinHandle<()>>,
messages_handle: Option<tokio::task::JoinHandle<()>>,
}
#[derive(Debug, Clone)]
struct MavlinkCameraInner {
component: MavlinkCameraComponent,
mavlink_stream_type: mavlink::common::VideoStreamType,
video_stream_uri: Url,
video_stream_name: String,
video_source_type: VideoSourceType,
}
impl MavlinkCamera {
#[instrument(level = "debug")]
pub async fn try_new(video_and_stream_information: &VideoAndStreamInformation) -> Result<Self> {
let inner = Arc::new(MavlinkCameraInner::try_new(video_and_stream_information)?);
let sender = crate::mavlink::manager::Manager::get_sender();
debug!("Starting MAVLink HeartBeat task...");
let inner_cloned = inner.clone();
let sender_cloned = sender.clone();
let heartbeat_handle = Some(tokio::spawn(async move {
debug!("MAVLink HeartBeat task started!");
match MavlinkCameraInner::heartbeat_loop(inner_cloned, sender_cloned).await {
Ok(_) => debug!("MAVLink HeartBeat task eneded with no errors"),
Err(error) => warn!("MAVLink HeartBeat task ended with error: {error:#?}"),
};
}));
debug!("Starting MAVLink Message task...");
let inner_cloned = inner.clone();
let sender_cloned = sender.clone();
let messages_handle = Some(tokio::spawn(async move {
debug!("MAVLink Message task started!");
match MavlinkCameraInner::messages_loop(inner_cloned, sender_cloned).await {
Ok(_) => debug!("MAVLink Message task eneded with no errors"),
Err(error) => warn!("MAVLink Message task ended with error: {error:#?}"),
};
}));
Ok(Self {
inner,
heartbeat_handle,
messages_handle,
})
}
}
impl MavlinkCameraInner {
#[instrument(level = "debug")]
pub fn try_new(video_and_stream_information: &VideoAndStreamInformation) -> Result<Self> {
let video_stream_uri = video_and_stream_information
.stream_information
.endpoints
.first()
.context("Empty URI list")?
.to_owned();
let mavlink_stream_type = match video_stream_uri.scheme() {
"rtsp" => mavlink::common::VideoStreamType::VIDEO_STREAM_TYPE_RTSP,
"udp" => mavlink::common::VideoStreamType::VIDEO_STREAM_TYPE_RTPUDP,
unsupported => {
return Err(anyhow!(
"Scheme {unsupported:#?} is not supported for a Mavlink Camera."
));
}
};
let video_stream_name = video_and_stream_information.name.clone();
let video_source_type = video_and_stream_information.video_source.clone();
let component_id = super::manager::Manager::new_component_id();
let component =
MavlinkCameraComponent::try_new(video_and_stream_information, component_id)?;
let this = Self {
component,
mavlink_stream_type,
video_stream_uri,
video_stream_name,
video_source_type,
};
debug!("Starting new MAVLink camera: {this:#?}");
Ok(this)
}
#[instrument(level = "debug")]
pub fn cam_definition_uri(&self) -> Option<Url> {
// Get the current remotely accessible link (from default interface)
// to our camera XML file.
// This can't be a parameter because the default network route might
// change between the time of the MavlinkCamera creation
// and the time MAVLink connection is negotiated with the other MAVLink
// systems.
let visible_qgc_ip_address = get_visible_qgc_address();
let address = cli::manager::server_address();
let server_port = address.split(':').collect::<Vec<&str>>()[1];
let video_source_path = self.video_source_type.inner().source_string();
Url::parse(&format!(
"http://{visible_qgc_ip_address}:{server_port}/xml?file={video_source_path}"
))
.ok()
}
#[instrument(level = "trace", skip(sender))]
#[instrument(level = "debug", skip_all, fields(component_id = camera.component.component_id))]
pub async fn heartbeat_loop(
camera: Arc<MavlinkCameraInner>,
sender: broadcast::Sender<Message>,
) -> Result<()> {
let component_id = camera.component.component_id;
let system_id = camera.component.system_id;
let mut period = tokio::time::interval(tokio::time::Duration::from_secs(1));
loop {
period.tick().await;
let header = mavlink::MavHeader {
system_id,
component_id,
..Default::default()
};
let message = MavMessage::HEARTBEAT(mavlink::common::HEARTBEAT_DATA {
custom_mode: 0,
mavtype: mavlink::common::MavType::MAV_TYPE_CAMERA,
autopilot: mavlink::common::MavAutopilot::MAV_AUTOPILOT_INVALID,
base_mode: mavlink::common::MavModeFlag::empty(),
system_status: mavlink::common::MavState::MAV_STATE_STANDBY,
mavlink_version: 0x3,
});
if let Err(error) = sender.send(Message::ToBeSent((header, message))) {
error!("Failed to send message: {error:?}");
continue;
}
}
}
#[instrument(level = "trace", skip(sender))]
#[instrument(level = "debug", skip_all, fields(component_id = camera.component.component_id))]
pub async fn messages_loop(
camera: Arc<MavlinkCameraInner>,
sender: broadcast::Sender<Message>,
) -> Result<()> {
let mut receiver = sender.subscribe();
use crate::mavlink::mavlink_camera::Message::Received;
loop {
match receiver.recv().await {
Ok(Received((header, message))) => {
trace!("Message received: {header:?}, {message:?}");
Self::handle_message(camera.clone(), sender.clone(), header, message).await;
}
Ok(Message::ToBeSent(_)) => (),
Err(error) => {
error!("Failed receiving from broadcast channel: {error:#?}. Resubscribing to the channel...");
receiver = receiver.resubscribe();
}
}
}
}
#[instrument(level = "trace", skip(sender))]
#[instrument(level = "debug", skip(sender, camera), fields(component_id = camera.component.component_id))]
async fn handle_message(
camera: Arc<MavlinkCameraInner>,
sender: broadcast::Sender<Message>,
header: MavHeader,
message: MavMessage,
) {
match &message {
MavMessage::COMMAND_LONG(data) => {
debug!("Received message");
Self::handle_command_long(&camera, sender, &header, data).await;
}
MavMessage::PARAM_EXT_SET(data) => {
debug!("Received message");
Self::handle_param_ext_set(&camera, sender, &header, data).await;
}
MavMessage::PARAM_EXT_REQUEST_READ(data) => {
debug!("Received message");
Self::handle_param_ext_request_read(&camera, sender, &header, data).await;
}
MavMessage::PARAM_EXT_REQUEST_LIST(data) => {
debug!("Received message");
Self::handle_param_ext_request_list(&camera, sender, &header, data).await;
}
MavMessage::HEARTBEAT(_data) => {
// We receive a bunch of heartbeat messages, we can ignore it, but as it can be useful for debugging.
trace!("Received heartbeat");
}
_ => {
// Any other message that is not a heartbeat or command_long
trace!("Received an unsupported message");
}
}
}
#[instrument(level = "trace", skip(sender))]
#[instrument(level = "debug", skip(sender, camera), fields(component_id = camera.component.component_id))]
async fn handle_command_long(
camera: &MavlinkCameraInner,
sender: broadcast::Sender<Message>,
their_header: &MavHeader,
data: &mavlink::common::COMMAND_LONG_DATA,
) {
#[instrument(level = "debug", skip(sender))]
fn send_ack(
sender: &broadcast::Sender<Message>,
our_header: mavlink::MavHeader,
their_header: &mavlink::MavHeader,
command: mavlink::common::MavCmd,
result: mavlink::common::MavResult,
) {
if let Err(error) = sender.send(Message::ToBeSent((
our_header,
MavMessage::COMMAND_ACK(mavlink::common::COMMAND_ACK_DATA {
command,
result,
target_system: their_header.system_id,
target_component: their_header.component_id,
..Default::default()
}),
))) {
warn!("Failed to send message: {error:?}");
}
}
let our_header = camera.component.header(None);
if data.target_system != our_header.system_id
|| data.target_component != our_header.component_id
{
trace!("Ignoring {data:?}, wrong command id or system id");
return;
}
match data.command {
mavlink::common::MavCmd::MAV_CMD_REQUEST_CAMERA_INFORMATION => {
let result = mavlink::common::MavResult::MAV_RESULT_ACCEPTED;
send_ack(&sender, our_header, their_header, data.command, result);
let message =
MavMessage::CAMERA_INFORMATION(mavlink::common::CAMERA_INFORMATION_DATA {
time_boot_ms: super::sys_info::sys_info().time_boot_ms,
firmware_version: 0,
focal_length: 0.0,
sensor_size_h: 0.0,
sensor_size_v: 0.0,
flags: mavlink::common::CameraCapFlags::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM,
resolution_h: camera.component.resolution_h,
resolution_v: camera.component.resolution_v,
cam_definition_version: 0,
vendor_name: from_string_to_u8_array_with_size_32(
&camera.component.vendor_name,
),
model_name: from_string_to_u8_array_with_size_32(
&camera.component.vendor_name,
),
lens_id: 0,
cam_definition_uri:
from_string_to_vec_char_with_defined_size_and_null_terminator(
camera.cam_definition_uri().unwrap().as_str(),
140,
),
});
if let Err(error) = sender.send(Message::ToBeSent((our_header, message))) {
warn!("Failed to send message: {error:?}");
}
}
mavlink::common::MavCmd::MAV_CMD_REQUEST_CAMERA_SETTINGS => {
let result = mavlink::common::MavResult::MAV_RESULT_ACCEPTED;
send_ack(&sender, our_header, their_header, data.command, result);
let message = MavMessage::CAMERA_SETTINGS(mavlink::common::CAMERA_SETTINGS_DATA {
time_boot_ms: super::sys_info::sys_info().time_boot_ms,
zoomLevel: 0.0,
focusLevel: 0.0,
mode_id: mavlink::common::CameraMode::CAMERA_MODE_VIDEO,
});
if let Err(error) = sender.send(Message::ToBeSent((our_header, message))) {
warn!("Failed to send message: {error:?}");
}
}
mavlink::common::MavCmd::MAV_CMD_REQUEST_STORAGE_INFORMATION => {
let result = mavlink::common::MavResult::MAV_RESULT_ACCEPTED;
send_ack(&sender, our_header, their_header, data.command, result);
let sys_info = super::sys_info::sys_info();
let message =
MavMessage::STORAGE_INFORMATION(mavlink::common::STORAGE_INFORMATION_DATA {
time_boot_ms: sys_info.time_boot_ms,
total_capacity: sys_info.total_capacity,
used_capacity: sys_info.used_capacity,
available_capacity: sys_info.available_capacity,
read_speed: 1000.0,
write_speed: 1000.0,
storage_id: 0,
storage_count: 0,
status: mavlink::common::StorageStatus::STORAGE_STATUS_READY,
});
if let Err(error) = sender.send(Message::ToBeSent((our_header, message))) {
warn!("Failed to send message: {error:?}");
}
}
mavlink::common::MavCmd::MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS => {
let result = mavlink::common::MavResult::MAV_RESULT_ACCEPTED;
send_ack(&sender, our_header, their_header, data.command, result);
let sys_info = super::sys_info::sys_info();
let message = MavMessage::CAMERA_CAPTURE_STATUS(
mavlink::common::CAMERA_CAPTURE_STATUS_DATA {
time_boot_ms: sys_info.time_boot_ms,
image_interval: 0.0,
recording_time_ms: 0,
available_capacity: sys_info.available_capacity,
image_status: 0,
video_status: 0,
image_count: 0,
},
);
if let Err(error) = sender.send(Message::ToBeSent((our_header, message))) {
warn!("Failed to send message: {error:?}");
}
}
mavlink::common::MavCmd::MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION => {
const ALL_CAMERAS: u8 = 0u8;
if data.param2 != (camera.component.stream_id as f32)
&& data.param2 != (ALL_CAMERAS as f32)
{
warn!("Unknown stream id: {:#?}.", data.param2);
let result = mavlink::common::MavResult::MAV_RESULT_UNSUPPORTED;
send_ack(&sender, our_header, their_header, data.command, result);
return;
}
let result = mavlink::common::MavResult::MAV_RESULT_ACCEPTED;
send_ack(&sender, our_header, their_header, data.command, result);
// The only important information here is the mavtype and uri variables, everything else can be fake
let message = MavMessage::VIDEO_STREAM_INFORMATION(
mavlink::common::VIDEO_STREAM_INFORMATION_DATA {
framerate: camera.component.framerate,
bitrate: camera.component.bitrate,
flags: get_stream_status_flag(&camera.component),
resolution_h: camera.component.resolution_h,
resolution_v: camera.component.resolution_v,
rotation: camera.component.rotation,
hfov: camera.component.hfov,
stream_id: camera.component.stream_id,
count: 0,
mavtype: camera.mavlink_stream_type,
name: from_string_to_char_array_with_size_32(&camera.video_stream_name),
uri: from_string_to_vec_char_with_defined_size_and_null_terminator(
camera.video_stream_uri.as_ref(),
140,
),
},
);
if let Err(error) = sender.send(Message::ToBeSent((our_header, message))) {
warn!("Failed to send message: {error:?}");
}
}
mavlink::common::MavCmd::MAV_CMD_RESET_CAMERA_SETTINGS => {
let result = mavlink::common::MavResult::MAV_RESULT_ACCEPTED;
send_ack(&sender, our_header, their_header, data.command, result);
let source_string = camera.video_source_type.inner().source_string();
let result = match crate::video::video_source::reset_controls(source_string) {
Ok(_) => mavlink::common::MavResult::MAV_RESULT_ACCEPTED,
Err(error) => {
error!("Failed to reset {source_string:?} controls with its default values as {:#?}:{:#?}. Reason: {error:?}", our_header.system_id, our_header.component_id);
mavlink::common::MavResult::MAV_RESULT_DENIED
}
};
send_ack(&sender, our_header, their_header, data.command, result);
}
mavlink::common::MavCmd::MAV_CMD_REQUEST_VIDEO_STREAM_STATUS => {
let result = mavlink::common::MavResult::MAV_RESULT_ACCEPTED;
send_ack(&sender, our_header, their_header, data.command, result);
// The only important information here is the mavtype and uri variables, everything else can be fake
let message =
MavMessage::VIDEO_STREAM_STATUS(mavlink::common::VIDEO_STREAM_STATUS_DATA {
framerate: camera.component.framerate,
bitrate: camera.component.bitrate,
flags: get_stream_status_flag(&camera.component),
resolution_h: camera.component.resolution_h,
resolution_v: camera.component.resolution_v,
rotation: camera.component.rotation,
hfov: camera.component.hfov,
stream_id: camera.component.stream_id,
});
if let Err(error) = sender.send(Message::ToBeSent((our_header, message))) {
warn!("Failed to send message: {error:?}");
}
}
mavlink::common::MavCmd::MAV_CMD_REQUEST_MESSAGE => {
let result = mavlink::common::MavResult::MAV_RESULT_UNSUPPORTED;
send_ack(&sender, our_header, their_header, data.command, result);
warn!("MAVLink message \"MAV_CMD_REQUEST_MESSAGE\" is not supported yet, please report this issue so we can prioritize it. Meanwhile, you can use the original definitions for the MAVLink Camera Protocol. Read more in: https://mavlink.io/en/services/camera.html#migration-notes-for-gcs--mavlink-sdks");
}
message => {
let result = mavlink::common::MavResult::MAV_RESULT_UNSUPPORTED;
send_ack(&sender, our_header, their_header, data.command, result);
trace!("Ignoring unknown message received: {message:?}")
}
}
}
#[instrument(level = "trace", skip(sender))]
#[instrument(level = "debug", skip(sender, camera), fields(component_id = camera.component.component_id))]
async fn handle_param_ext_set(
camera: &MavlinkCameraInner,
sender: broadcast::Sender<Message>,
header: &MavHeader,
data: &mavlink::common::PARAM_EXT_SET_DATA,
) {
#[instrument(level = "debug", skip(sender))]
fn send_ack(
sender: &broadcast::Sender<Message>,
our_header: mavlink::MavHeader,
data: &mavlink::common::PARAM_EXT_SET_DATA,
result: mavlink::common::ParamAck,
) {
if let Err(error) = sender.send(Message::ToBeSent((
our_header,
MavMessage::PARAM_EXT_ACK(mavlink::common::PARAM_EXT_ACK_DATA {
param_id: data.param_id,
param_value: data.param_value.clone(),
param_type: data.param_type,
param_result: result,
}),
))) {
warn!("Failed to send message: {error:?}");
}
}
let our_header = camera.component.header(None);
if data.target_system != our_header.system_id
|| data.target_component != our_header.component_id
{
trace!("Ignoring {data:?}, wrong command id or system id");
return;
}
let control_id = control_id_from_param_id(&data.param_id);
let control_value = control_value_from_param_value(&data.param_value, &data.param_type);
let (Some(control_id), Some(control_value)) = (control_id, control_value) else {
let result = mavlink::common::ParamAck::PARAM_ACK_VALUE_UNSUPPORTED;
send_ack(&sender, our_header, data, result);
return;
};
let result = match camera
.video_source_type
.inner()
.set_control_by_id(control_id, control_value)
{
Ok(_) => mavlink::common::ParamAck::PARAM_ACK_ACCEPTED,
Err(error) => {
error!("Failed to set parameter {control_id:?} with value {control_value:?} for {:#?}. Reason: {error:?}", our_header.component_id);
mavlink::common::ParamAck::PARAM_ACK_FAILED
}
};
send_ack(&sender, our_header, data, result);
}
#[instrument(level = "trace", skip(sender))]
#[instrument(level = "debug", skip(sender, camera), fields(component_id = camera.component.component_id))]
async fn handle_param_ext_request_read(
camera: &MavlinkCameraInner,
sender: broadcast::Sender<Message>,
header: &MavHeader,
data: &mavlink::common::PARAM_EXT_REQUEST_READ_DATA,
) {
let our_header = camera.component.header(None);
if data.target_system != our_header.system_id
|| data.target_component != our_header.component_id
{
trace!("Ignoring {data:?}, wrong command id or system id");
return;
}
let controls = camera.video_source_type.inner().controls();
let Some((param_index, control_id)) = get_param_index_and_control_id(data, &controls)
else {
return;
};
let param_id = param_id_from_control_id(control_id);
let control_value = match camera
.video_source_type
.inner()
.control_value_by_id(control_id)
{
Ok(value) => value,
Err(error) => {
error!("Failed to get parameter {control_id:?}: {error:?}");
return;
}
};
let param_value = param_value_from_control_value(control_value, 128);
let our_header = camera.component.header(None);
let message = MavMessage::PARAM_EXT_VALUE(mavlink::common::PARAM_EXT_VALUE_DATA {
param_count: 1,
param_index,
param_id,
param_value,
param_type: mavlink::common::MavParamExtType::MAV_PARAM_EXT_TYPE_INT64,
});
if let Err(error) = sender.send(Message::ToBeSent((our_header, message))) {
warn!("Failed to send message: {error:?}");
}
}
#[instrument(level = "trace", skip(sender))]
#[instrument(level = "debug", skip(sender, camera), fields(component_id = camera.component.component_id))]
async fn handle_param_ext_request_list(
camera: &MavlinkCameraInner,
sender: broadcast::Sender<Message>,
header: &MavHeader,
data: &mavlink::common::PARAM_EXT_REQUEST_LIST_DATA,
) {
let our_header = camera.component.header(None);
if data.target_system != our_header.system_id
|| data.target_component != our_header.component_id
{
trace!("Ignoring {data:?}, wrong command id or system id");
return;
}
let controls = camera.video_source_type.inner().controls();
controls
.iter()
.enumerate()
.for_each(|(param_index, control)| {
let param_id = param_id_from_control_id(control.id);
let control_value = match camera
.video_source_type
.inner()
.control_value_by_id(control.id)
{
Ok(value) => value,
Err(error) => {
error!("Failed to get parameter {:?}: {error:?}", control.id);
return;
}
};
let param_value = param_value_from_control_value(control_value, 128);
let our_header = camera.component.header(None);
let message = MavMessage::PARAM_EXT_VALUE(mavlink::common::PARAM_EXT_VALUE_DATA {
param_count: controls.len() as u16,
param_index: param_index as u16,
param_id,
param_value,
param_type: mavlink::common::MavParamExtType::MAV_PARAM_EXT_TYPE_INT64,
});
if let Err(error) = sender.send(Message::ToBeSent((our_header, message))) {
warn!("Failed to send message: {error:?}");
}
});
}
}
impl Drop for MavlinkCamera {
#[instrument(level = "debug", skip(self))]
fn drop(&mut self) {
debug!("Dropping MavlinkCameraHandle...");
if let Some(handle) = self.heartbeat_handle.take() {
if !handle.is_finished() {
handle.abort();
tokio::spawn(async move {
let _ = handle.await;
debug!("Mavlink Heartbeat task aborted");
});
} else {
debug!("Mavlink Heartbeat task nicely finished!");
}
}
if let Some(handle) = self.messages_handle.take() {
if !handle.is_finished() {
handle.abort();
tokio::spawn(async move {
let _ = handle.await;
debug!("Mavlink Message task aborted");
});
} else {
debug!("Mavlink Message task nicely finished!");
}
}
super::manager::Manager::drop_id(self.inner.component.component_id);
debug!("MavlinkCameraHandle Dropped!");
}
}