mavrouter 0.1.5

MAVLink router
Documentation
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
use crate::error::{Result, RouterError};
use crate::filter::EndpointFilters;
use serde::Deserialize;
use std::path::Path;
use std::str::FromStr;
use tokio::fs;

/// Configuration for MAVLink router.
///
/// Loaded from TOML file using [`Config::load`].
///
/// # Example
/// ```toml
/// [general]
/// tcp_port = 5760
/// dedup_period_ms = 100
/// log = "logs"
/// log_telemetry = true
/// bus_capacity = 1000
/// routing_table_ttl_secs = 300
/// routing_table_prune_interval_secs = 60
///
/// [[endpoint]]
/// type = "serial"
/// device = "/dev/ttyACM0"
/// baud = 115200
///
/// [[endpoint]]
/// type = "udp"
/// address = "0.0.0.0:14550"
/// mode = "server"
///
/// [[endpoint]]
/// type = "tcp"
/// address = "127.0.0.1:5761"
/// mode = "client"
/// ```
#[derive(Debug, Deserialize)]
pub struct Config {
    /// General router configuration.
    #[serde(default)]
    pub general: GeneralConfig,
    /// List of endpoint configurations.
    #[serde(default)]
    pub endpoint: Vec<EndpointConfig>,
}

/// General router configuration.
#[derive(Debug, Deserialize)]
pub struct GeneralConfig {
    /// Optional TCP server port for general GCS connections.
    pub tcp_port: Option<u16>,
    /// Message deduplication period in milliseconds. Messages with the same
    /// system_id, component_id, message_id, and data will be ignored if
    /// received within this period.
    pub dedup_period_ms: Option<u64>,
    /// Optional path to a directory for logging MAVLink traffic.
    pub log: Option<String>,
    /// Whether to log telemetry data (MAVLink messages) to files.
    #[serde(default)]
    pub log_telemetry: bool,
    /// Capacity of the internal message bus. Typical values are 1000-10000.
    #[serde(default = "default_bus_capacity")]
    pub bus_capacity: usize,
    /// Time-to-live (TTL) for entries in the routing table, in seconds.
    /// Entries older than this will be pruned.
    #[serde(default = "default_routing_table_ttl_secs")]
    pub routing_table_ttl_secs: u64,
    /// Interval at which the routing table is pruned, in seconds.
    #[serde(default = "default_routing_table_prune_interval_secs")]
    pub routing_table_prune_interval_secs: u64,
    /// Stats history retention period in seconds.
    /// Default 86400 seconds (24 hours). Set to 0 to disable stats.
    /// Note: Memory usage ≈ retention_secs * 24 bytes.
    #[serde(default = "default_stats_retention_secs")]
    pub stats_retention_secs: u64,
    /// Stats sampling interval in seconds. Default 1 second.
    #[serde(default = "default_stats_sample_interval_secs")]
    pub stats_sample_interval_secs: u64,
    /// Stats log output interval in seconds. Default 60 seconds.
    #[serde(default = "default_stats_log_interval_secs")]
    pub stats_log_interval_secs: u64,
    /// Path to the Unix socket for querying stats.
    /// Default: None (disabled). Set to a path string to enable (e.g., "/tmp/mavrouter.sock").
    #[serde(default)]
    #[cfg_attr(not(unix), allow(dead_code))]
    pub stats_socket_path: Option<String>,
}

fn default_bus_capacity() -> usize {
    5000
}

impl Default for GeneralConfig {
    fn default() -> Self {
        Self {
            tcp_port: None,
            dedup_period_ms: None,
            log: None,
            log_telemetry: false,
            bus_capacity: default_bus_capacity(),
            routing_table_ttl_secs: default_routing_table_ttl_secs(),
            routing_table_prune_interval_secs: default_routing_table_prune_interval_secs(),
            stats_retention_secs: default_stats_retention_secs(),
            stats_sample_interval_secs: default_stats_sample_interval_secs(),
            stats_log_interval_secs: default_stats_log_interval_secs(),
            stats_socket_path: None,
        }
    }
}
fn default_routing_table_ttl_secs() -> u64 {
    300
}
fn default_routing_table_prune_interval_secs() -> u64 {
    60
}
fn default_stats_retention_secs() -> u64 {
    86400
}
fn default_stats_sample_interval_secs() -> u64 {
    1
}
fn default_stats_log_interval_secs() -> u64 {
    60
}

#[derive(Debug, Deserialize, Clone)]
#[serde(tag = "type")]
#[serde(rename_all = "lowercase")]
/// Configuration for a specific communication endpoint.
pub enum EndpointConfig {
    /// UDP endpoint configuration.
    Udp {
        /// Address for the UDP endpoint (e.g., "0.0.0.0:14550").
        address: String,
        /// Operating mode for the UDP endpoint (client or server).
        #[serde(default = "default_mode_server")]
        mode: EndpointMode,
        /// Filters to apply to messages passing through this endpoint.
        #[serde(flatten)]
        filters: EndpointFilters,
    },
    /// TCP endpoint configuration.
    Tcp {
        /// Address for the TCP endpoint (e.g., "127.0.0.1:5761").
        address: String,
        /// Operating mode for the TCP endpoint (client or server).
        #[serde(default = "default_mode_client")]
        mode: EndpointMode,
        /// Filters to apply to messages passing through this endpoint.
        #[serde(flatten)]
        filters: EndpointFilters,
    },
    /// Serial endpoint configuration.
    Serial {
        /// Device path for the serial port (e.g., "/dev/ttyACM0" or "COM1").
        device: String,
        /// Baud rate for the serial connection.
        baud: u32,
        /// Filters to apply to messages passing through this endpoint.
        #[serde(flatten)]
        filters: EndpointFilters,
    },
}

#[derive(Debug, Deserialize, PartialEq, Eq, Clone)]
#[serde(rename_all = "lowercase")]
/// Operating mode for network endpoints.
pub enum EndpointMode {
    /// Connects as a client to a remote server.
    Client,
    /// Listens for incoming connections as a server.
    Server,
}

fn default_mode_server() -> EndpointMode {
    EndpointMode::Server
}
fn default_mode_client() -> EndpointMode {
    EndpointMode::Client
}

impl Config {
    /// Parses router configuration from a TOML string.
    ///
    /// This is useful for programmatically generating configurations without
    /// needing to write temporary files.
    ///
    /// # Arguments
    ///
    /// * `toml` - A string containing valid TOML configuration.
    ///
    /// # Errors
    ///
    /// Returns a `RouterError` if the string cannot be parsed or validation fails.
    ///
    /// # Example
    ///
    /// ```
    /// use mavrouter::config::Config;
    /// use std::str::FromStr;
    ///
    /// let toml = r#"
    /// [general]
    /// bus_capacity = 1000
    ///
    /// [[endpoint]]
    /// type = "udp"
    /// address = "0.0.0.0:14550"
    /// mode = "server"
    /// "#;
    ///
    /// let config = Config::from_str(toml).expect("valid config");
    /// assert_eq!(config.endpoint.len(), 1);
    /// ```
    pub fn parse(toml: &str) -> Result<Self> {
        let config: Config = toml::from_str(toml)
            .map_err(|e| RouterError::config(format!("Failed to parse config: {}", e)))?;

        config.validate()?;

        Ok(config)
    }

    /// Loads the router configuration from a TOML file.
    ///
    /// # Arguments
    ///
    /// * `path` - The path to the TOML configuration file.
    ///
    /// # Errors
    ///
    /// Returns a `RouterError` if the file cannot be read or parsed,
    /// or if the configuration fails validation.
    pub async fn load(path: impl AsRef<Path>) -> Result<Self> {
        let path_str = path.as_ref().display().to_string();
        let content = fs::read_to_string(path.as_ref())
            .await
            .map_err(|e| RouterError::filesystem(&path_str, e))?;

        Self::parse(&content)
    }

    /// Validates the loaded configuration to check for common errors,
    /// such as duplicate ports, invalid addresses, or invalid baud rates.
    ///
    /// # Errors
    ///
    /// Returns a `RouterError::Config` if the configuration contains invalid or
    /// conflicting settings.
    #[allow(unused_variables)] // 'device' is unused on non-Unix platforms
    pub fn validate(&self) -> Result<()> {
        // Track (protocol, port) pairs -- TCP and UDP on the same port are distinct OS resources
        let mut ports: std::collections::HashSet<(&str, u16)> = std::collections::HashSet::new();

        if let Some(tcp_port) = self.general.tcp_port {
            ports.insert(("tcp", tcp_port));
        }

        for (i, endpoint) in self.endpoint.iter().enumerate() {
            match endpoint {
                EndpointConfig::Tcp { address, .. } => {
                    let addr = address.parse::<std::net::SocketAddr>().map_err(|e| {
                        RouterError::config(format!(
                            "Invalid address in endpoint {}: {} ({})",
                            i, address, e
                        ))
                    })?;

                    if !ports.insert(("tcp", addr.port())) {
                        return Err(RouterError::config(format!(
                            "Duplicate TCP port {} in endpoint {}",
                            addr.port(),
                            i
                        )));
                    }
                }
                EndpointConfig::Udp { address, .. } => {
                    let addr = address.parse::<std::net::SocketAddr>().map_err(|e| {
                        RouterError::config(format!(
                            "Invalid address in endpoint {}: {} ({})",
                            i, address, e
                        ))
                    })?;

                    if !ports.insert(("udp", addr.port())) {
                        return Err(RouterError::config(format!(
                            "Duplicate UDP port {} in endpoint {}",
                            addr.port(),
                            i
                        )));
                    }
                }
                EndpointConfig::Serial { device, baud, .. } => {
                    // Verify baud rate
                    if *baud < 300 || *baud > 4_000_000 {
                        return Err(RouterError::config(format!(
                            "Invalid baud rate in endpoint {}: {} (must be 300-4000000)",
                            i, baud
                        )));
                    }

                    #[cfg(unix)]
                    if !std::path::Path::new(device).exists() {
                        tracing::warn!("Serial device {} does not exist (endpoint {})", device, i);
                    }
                }
            }

            // Validate filters
            let filters = match endpoint {
                EndpointConfig::Udp { filters, .. } => filters,
                EndpointConfig::Tcp { filters, .. } => filters,
                EndpointConfig::Serial { filters, .. } => filters,
            };

            // Helper closure to check msg_ids
            let check_msg_ids = |ids: &ahash::AHashSet<u32>, type_str: &str| -> Result<()> {
                for &msg_id in ids {
                    if msg_id > 65535 {
                        return Err(RouterError::config(format!(
                            "Invalid {} msg_id in endpoint {}: {} (must be <= 65535)",
                            type_str, i, msg_id
                        )));
                    }
                }
                Ok(())
            };

            check_msg_ids(&filters.allow_msg_id_out, "allow_out")?;
            check_msg_ids(&filters.block_msg_id_out, "block_out")?;
            check_msg_ids(&filters.allow_msg_id_in, "allow_in")?;
            check_msg_ids(&filters.block_msg_id_in, "block_in")?;
        }

        if self.general.bus_capacity < 10 {
            return Err(RouterError::config(format!(
                "bus_capacity too small: {}",
                self.general.bus_capacity
            )));
        }

        if self.general.bus_capacity > 1_000_000 {
            return Err(RouterError::config(format!(
                "bus_capacity too large: {} (must be <= 1000000)",
                self.general.bus_capacity
            )));
        }

        if self.general.routing_table_prune_interval_secs == 0 {
            return Err(RouterError::config(
                "routing_table_prune_interval_secs must be greater than 0".to_string(),
            ));
        }

        Ok(())
    }
}

impl FromStr for Config {
    type Err = RouterError;

    /// Parses router configuration from a TOML string.
    ///
    /// This implements the standard `FromStr` trait, allowing the use of
    /// `str.parse::<Config>()` or `Config::from_str(s)`.
    ///
    /// # Example
    ///
    /// ```
    /// use mavrouter::config::Config;
    /// use std::str::FromStr;
    ///
    /// let toml = r#"
    /// [[endpoint]]
    /// type = "udp"
    /// address = "0.0.0.0:14550"
    /// "#;
    ///
    /// let config: Config = toml.parse().expect("valid config");
    /// ```
    fn from_str(s: &str) -> std::result::Result<Self, Self::Err> {
        Config::parse(s)
    }
}

#[cfg(test)]
#[allow(clippy::expect_used)]
mod tests {
    use super::*;

    #[test]
    fn test_duplicate_tcp_port_detection() {
        let config = Config {
            general: GeneralConfig {
                tcp_port: Some(5760),
                ..Default::default()
            },
            endpoint: vec![EndpointConfig::Tcp {
                address: "127.0.0.1:5760".to_string(),
                mode: EndpointMode::Client,
                filters: EndpointFilters::default(),
            }],
        };

        assert!(
            config.validate().is_err(),
            "Should detect duplicate TCP port"
        );
    }

    #[test]
    fn test_cross_protocol_same_port_allowed() {
        // TCP and UDP on the same port should be allowed (different OS resources)
        let config = Config {
            general: GeneralConfig {
                tcp_port: Some(5760),
                ..Default::default()
            },
            endpoint: vec![EndpointConfig::Udp {
                address: "127.0.0.1:5760".to_string(),
                mode: EndpointMode::Server,
                filters: EndpointFilters::default(),
            }],
        };

        assert!(
            config.validate().is_ok(),
            "TCP and UDP on the same port should be allowed"
        );
    }

    #[test]
    fn test_bus_capacity_too_large() {
        let config = Config {
            general: GeneralConfig {
                bus_capacity: 2_000_000,
                ..Default::default()
            },
            endpoint: vec![],
        };
        assert!(config.validate().is_err());
    }

    #[test]
    fn test_prune_interval_zero() {
        let config = Config {
            general: GeneralConfig {
                routing_table_prune_interval_secs: 0,
                ..Default::default()
            },
            endpoint: vec![],
        };
        assert!(
            config.validate().is_err(),
            "prune_interval_secs = 0 should be rejected"
        );
    }

    #[test]
    fn test_invalid_baud_rate() {
        let config = Config {
            general: GeneralConfig::default(),
            endpoint: vec![EndpointConfig::Serial {
                device: "/dev/ttyUSB0".to_string(),
                baud: 100, // Too low
                filters: EndpointFilters::default(),
            }],
        };
        assert!(config.validate().is_err());

        let config_high = Config {
            general: GeneralConfig::default(),
            endpoint: vec![EndpointConfig::Serial {
                device: "/dev/ttyUSB0".to_string(),
                baud: 5_000_000, // Too high
                filters: EndpointFilters::default(),
            }],
        };
        assert!(config_high.validate().is_err());
    }

    #[test]
    fn test_valid_baud_rate() {
        let config = Config {
            general: GeneralConfig::default(),
            endpoint: vec![EndpointConfig::Serial {
                device: "/dev/ttyUSB0".to_string(),
                baud: 115200,
                filters: EndpointFilters::default(),
            }],
        };
        assert!(config.validate().is_ok());
    }

    #[test]
    fn test_invalid_address() {
        let config = Config {
            general: GeneralConfig::default(),
            endpoint: vec![EndpointConfig::Tcp {
                address: "not_an_address".to_string(),
                mode: EndpointMode::Client,
                filters: EndpointFilters::default(),
            }],
        };
        assert!(config.validate().is_err());
    }

    #[test]
    fn test_bus_capacity_too_small() {
        let config = Config {
            general: GeneralConfig {
                bus_capacity: 5, // Too small
                ..Default::default()
            },
            endpoint: vec![],
        };
        assert!(config.validate().is_err());
    }

    #[test]
    fn test_valid_config() {
        let config = Config {
            general: GeneralConfig {
                tcp_port: Some(5760),
                bus_capacity: 1000,
                ..Default::default()
            },
            endpoint: vec![
                EndpointConfig::Udp {
                    address: "0.0.0.0:14550".to_string(),
                    mode: EndpointMode::Server,
                    filters: EndpointFilters::default(),
                },
                EndpointConfig::Tcp {
                    address: "127.0.0.1:5761".to_string(),
                    mode: EndpointMode::Client,
                    filters: EndpointFilters::default(),
                },
            ],
        };
        assert!(config.validate().is_ok());
    }

    #[test]
    fn test_from_str_valid() {
        let toml = r#"
[general]
bus_capacity = 1000

[[endpoint]]
type = "udp"
address = "0.0.0.0:14550"
mode = "server"
"#;
        let config = Config::from_str(toml).expect("should parse valid TOML");
        assert_eq!(config.endpoint.len(), 1);
        assert_eq!(config.general.bus_capacity, 1000);
    }

    #[test]
    fn test_from_str_invalid_toml() {
        let toml = "this is not valid toml {{{{";
        assert!(Config::from_str(toml).is_err());
    }

    #[test]
    fn test_from_str_empty() {
        let toml = "";
        // Empty config should be valid (all defaults)
        let config = Config::from_str(toml).expect("empty config should use defaults");
        assert!(config.endpoint.is_empty());
        assert_eq!(config.general.bus_capacity, 5000); // default
    }

    #[test]
    fn test_from_str_validation_error() {
        let toml = r#"
[general]
bus_capacity = 5

[[endpoint]]
type = "udp"
address = "0.0.0.0:14550"
"#;
        // bus_capacity too small should fail validation
        assert!(Config::from_str(toml).is_err());
    }
}