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
//! Serial endpoint for MAVLink communications.
//!
//! This module handles MAVLink traffic over serial ports, providing
//! reliable communication with connected flight controllers or other
//! serial MAVLink devices. It supports automatic reconnection if the
//! serial port connection is lost.
use crateConcurrentDedup;
use crate;
use crate;
use crateEndpointFilters;
use crate;
use crateRoutingTable;
use RwLock;
use Arc;
use broadcast;
use SerialPortBuilderExt;
use CancellationToken;
use info;
use warn;
/// Runs the serial endpoint logic, continuously attempting to open and
/// communicate over the specified serial device.
///
/// This function manages the lifecycle of a serial connection:
/// - It attempts to open the serial port with the given baud rate.
/// - If successful, it enters a loop to process incoming and outgoing MAVLink messages.
/// - If the port cannot be opened or the connection is lost, it retries after a delay.
/// - It gracefully shuts down when the `CancellationToken` is cancelled.
///
/// # Arguments
///
/// * `id` - Unique identifier for this endpoint.
/// * `device` - The path to the serial device (e.g., "/dev/ttyACM0" on Linux, "COM1" on Windows).
/// * `baud` - The baud rate for the serial connection (e.g., 115200).
/// * `bus_tx` - Sender half of the message bus for sending `RoutedMessage`s to other endpoints.
/// * `bus_rx` - Receiver half of the message bus for receiving `RoutedMessage`s from other endpoints.
/// * `routing_table` - Shared `RoutingTable` to update and query routing information.
/// * `dedup` - Shared `Dedup` instance for message deduplication.
/// * `filters` - `EndpointFilters` to apply for this specific endpoint.
/// * `token` - `CancellationToken` to signal graceful shutdown.
///
/// # Returns
///
/// A `Result` indicating success or failure. The function will run indefinitely
/// until the `CancellationToken` is cancelled or a critical, unrecoverable error occurs.
///
/// # Errors
///
/// Returns an `anyhow::Error` if a critical error occurs that prevents further operation,
/// such as a permanent serial port configuration issue.
pub async
/// Opens the specified serial port and runs the stream processing loop.
///
/// This is a helper function that attempts to open a serial port and
/// then delegates to `run_stream_loop` to handle the actual MAVLink
/// message processing.
///
/// # Arguments
///
/// * `device` - The path to the serial device.
/// * `baud` - The baud rate for the serial connection.
/// * `bus_rx` - Receiver half of the message bus for outgoing messages.
/// * `core` - The `EndpointCore` instance containing shared resources and logic.
/// * `token` - `CancellationToken` to signal graceful shutdown.
///
/// # Returns
///
/// A `Result` indicating success or failure to open the port or if `run_stream_loop`
/// encounters an error.
///
/// # Errors
///
/// Returns an `anyhow::Error` if the serial port cannot be opened or configured.
async