diff --git a/Cargo.lock b/Cargo.lock index dcdab87..04137f6 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -423,17 +423,6 @@ version = "1.1.1" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "1181e1e0d1fce796a03db1ae795d67167da795f9cf4a39c37589e85ef57f26d3" -[[package]] -name = "atty" -version = "0.2.14" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d9b39be18770d11421cdb1b9947a45dd3f37e93092cbf377614828a319d5fee8" -dependencies = [ - "hermit-abi 0.1.19", - "libc", - "winapi", -] - [[package]] name = "autocfg" version = "1.1.0" @@ -707,21 +696,6 @@ dependencies = [ "libloading 0.7.4", ] -[[package]] -name = "clap" -version = "3.2.25" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4ea181bf566f71cb9a5d17a59e1871af638180a18fb0035c92ae62b705207123" -dependencies = [ - "atty", - "bitflags 1.3.2", - "clap_lex 0.2.4", - "indexmap 1.9.3", - "strsim", - "termcolor", - "textwrap", -] - [[package]] name = "clap" version = "4.4.11" @@ -740,7 +714,7 @@ checksum = "a216b506622bb1d316cd51328dce24e07bdff4a6128a47c7e7fad11878d5adbb" dependencies = [ "anstream", "anstyle", - "clap_lex 0.6.0", + "clap_lex", "strsim", ] @@ -756,15 +730,6 @@ dependencies = [ "syn 2.0.33", ] -[[package]] -name = "clap_lex" -version = "0.2.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "2850f2f5a82cbf437dd5af4d49848fbdfc27c157c3d010345776f952765261c5" -dependencies = [ - "os_str_bytes", -] - [[package]] name = "clap_lex" version = "0.6.0" @@ -1436,15 +1401,6 @@ version = "0.4.1" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "95505c38b4572b2d910cecb0281560f54b440a19336cbbcb27bf6ce6adc6f5a8" -[[package]] -name = "hermit-abi" -version = "0.1.19" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "62b467343b94ba476dcb2500d242dadbb39557df889310ac77c5d99100aaac33" -dependencies = [ - "libc", -] - [[package]] name = "hermit-abi" version = "0.3.2" @@ -1686,7 +1642,7 @@ version = "1.0.11" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "eae7b9aee968036d54dce06cebaefd919e4472e753296daccd6d344e3e2df0c2" dependencies = [ - "hermit-abi 0.3.2", + "hermit-abi", "libc", "windows-sys 0.48.0", ] @@ -1712,7 +1668,7 @@ version = "0.4.9" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "cb0889898416213fab133e1d33a0e5858a48177452750691bde3666d0fdbaf8b" dependencies = [ - "hermit-abi 0.3.2", + "hermit-abi", "rustix 0.38.13", "windows-sys 0.48.0", ] @@ -1762,7 +1718,7 @@ dependencies = [ "anyhow", "base64 0.21.4", "bytecount", - "clap 4.4.11", + "clap", "fancy-regex", "fraction", "getrandom 0.2.10", @@ -2077,7 +2033,7 @@ version = "1.16.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "4161fcb6d602d4d2081af7c3a45852d875a03dd337a6bfdd6e06407b61342a43" dependencies = [ - "hermit-abi 0.3.2", + "hermit-abi", "libc", ] @@ -2123,12 +2079,6 @@ dependencies = [ "num-traits", ] -[[package]] -name = "os_str_bytes" -version = "6.6.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e2355d85b9a3786f481747ced0e0ff2ba35213a1f9bd406ed906554d7af805a1" - [[package]] name = "parking" version = "2.1.0" @@ -3431,12 +3381,6 @@ dependencies = [ "winapi-util", ] -[[package]] -name = "textwrap" -version = "0.16.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "222a222a5bfe1bba4a77b45ec488a741b3cb8872e5e499451fd7d0129c9c7c3d" - [[package]] name = "thiserror" version = "1.0.48" @@ -4256,10 +4200,11 @@ version = "0.11.0-dev" dependencies = [ "async-liveliness-monitor", "async-std", - "clap 3.2.25", + "clap", "env_logger", "lazy_static", "log", + "serde", "serde_json", "zenoh", "zenoh-plugin-rest", @@ -4549,7 +4494,7 @@ dependencies = [ "anyhow", "async-std", "base64 0.21.4", - "clap 4.4.11", + "clap", "env_logger", "flume", "futures", @@ -4688,7 +4633,7 @@ source = "git+https://github.com/eclipse-zenoh/zenoh?branch=master#780ec606ba400 dependencies = [ "async-std", "async-trait", - "clap 4.4.11", + "clap", "const_format", "flume", "futures", diff --git a/Cargo.toml b/Cargo.toml index 5c5f7cd..164de63 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -29,7 +29,7 @@ async-std = "=1.12.0" async-trait = "0.1.66" bincode = "1.3.3" cdr = "0.2.4" -clap = "3.2.23" +clap = "4.4.11" cyclors = "0.2.0" derivative = "2.2.0" env_logger = "0.10.0" diff --git a/zenoh-bridge-ros2dds/Cargo.toml b/zenoh-bridge-ros2dds/Cargo.toml index 15b0eee..44f129a 100644 --- a/zenoh-bridge-ros2dds/Cargo.toml +++ b/zenoh-bridge-ros2dds/Cargo.toml @@ -28,12 +28,13 @@ dds_shm = ["zenoh-plugin-ros2dds/dds_shm"] [dependencies] async-std = { workspace = true, features = ["unstable", "attributes"] } async-liveliness-monitor = { workspace = true } -clap = { workspace = true } +clap = { workspace = true, features = ["derive", "env"] } env_logger = { workspace = true } lazy_static = { workspace = true } log = { workspace = true } +serde = { workspace = true } serde_json = { workspace = true } -zenoh = { workspace = true } +zenoh = { workspace = true } zenoh-plugin-rest = { workspace = true } zenoh-plugin-trait = { workspace = true } zenoh-plugin-ros2dds = { path = "../zenoh-plugin-ros2dds/", default-features = false } diff --git a/zenoh-bridge-ros2dds/src/bridge_args.rs b/zenoh-bridge-ros2dds/src/bridge_args.rs new file mode 100644 index 0000000..6381b4d --- /dev/null +++ b/zenoh-bridge-ros2dds/src/bridge_args.rs @@ -0,0 +1,151 @@ +// +// Copyright (c) 2022 ZettaScale Technology +// +// This program and the accompanying materials are made available under the +// terms of the Eclipse Public License 2.0 which is available at +// http://www.eclipse.org/legal/epl-2.0, or the Apache License, Version 2.0 +// which is available at https://www.apache.org/licenses/LICENSE-2.0. +// +// SPDX-License-Identifier: EPL-2.0 OR Apache-2.0 +// +// Contributors: +// ZettaScale Zenoh Team, +// +use crate::zenoh_args::CommonArgs; +use clap::builder::FalseyValueParser; +use zenoh::config::Config; +use zenoh::prelude::*; + +// +// All Bridge arguments +// +#[derive(clap::Parser, Clone, Debug)] +#[command(version=zenoh_plugin_ros2dds::GIT_VERSION, + long_version=zenoh_plugin_ros2dds::LONG_VERSION.as_str(), + about="Zenoh bridge for ROS 2 with a DDS RMW", +)] +pub struct BridgeArgs { + #[command(flatten)] + pub session_args: CommonArgs, + /// The identifier (as an hexadecimal string, with odd number of chars - e.g.: 0A0B23...) that zenohd must use. + /// WARNING: this identifier must be unique in the system and must be 16 bytes maximum (32 chars)! + /// If not set, a random UUIDv4 will be used. + #[arg(short, long, verbatim_doc_comment)] + pub id: Option, + /// A ROS 2 namespace to be used by the "zenoh_bridge_dds" node' + #[arg(short, long)] + pub namespace: Option, + /// The DDS Domain ID. Default to $ROS_DOMAIN_ID environment variable if defined, or to 0 otherwise. + #[arg(short, long, default_value("0"), env("ROS_DOMAIN_ID"))] + pub domain: u32, + /// Configure CycloneDDS to use only the localhost interface. If not set, a $ROS_LOCALHOST_ONLY=1 environment variable activates this option. + /// When this flag is not active, CycloneDDS will pick the interface defined in "$CYCLONEDDS_URI" configuration, or automatically choose one. + #[arg( + long, + env("ROS_LOCALHOST_ONLY"), + value_parser(FalseyValueParser::new()), + verbatim_doc_comment + )] + pub ros_localhost_only: bool, + /// Configure CycloneDDS to use Iceoryx shared memory. If not set, CycloneDDS will instead use any shared memory settings defined in "$CYCLONEDDS_URI" configuration. + #[cfg(feature = "dds_shm")] + #[arg(long)] + pub dds_enable_shm: bool, + /// Specifies a maximum frequency of publications routing over zenoh for a set of Publishers. + /// The string must have the format "=": + /// - "regex" is a regular expression matching a Publisher interface name + /// - "float" is the maximum frequency in Hertz; if publication rate is higher, downsampling will occur when routing. + /// Repeat this option to configure several topics expressions with a max frequency. + #[arg(long, value_name = "REGEX=FLOAT", verbatim_doc_comment)] + pub pub_max_frequency: Vec, + /// A float in seconds that will be used as a timeout when the bridge queries any other remote bridge + /// for discovery information and for historical data for TRANSIENT_LOCAL DDS Readers it serves + /// (i.e. if the query to the remote bridge exceed the timeout, some historical samples might be not routed to the Readers, but the route will not be blocked forever). + /// This value overwrites the value possibly set in configuration file under 'plugins/ros2dds/queries_timeout/default' key [default: 5.0]. + #[arg(long, value_name = "FLOAT", verbatim_doc_comment)] + pub queries_timeout_default: Option, + + /// Configures HTTP interface for the REST API (disabled by default, setting this option enables it). Accepted values: + /// - a port number + /// - a string with format `:` (to bind the HTTP server to a specific interface). + #[arg(short, long, value_name = "PORT | IP:PORT", verbatim_doc_comment)] + pub rest_http_port: Option, + /// Experimental!! Run a watchdog thread that monitors the bridge's async executor and + /// reports as error log any stalled status during the specified period [default: 1.0 second] + #[arg(short, long, value_name = "FLOAT", default_missing_value = "1.0")] + pub watchdog: Option>, +} + +impl From for Config { + fn from(value: BridgeArgs) -> Self { + (&value).into() + } +} + +impl From<&BridgeArgs> for Config { + fn from(args: &BridgeArgs) -> Self { + let mut config = (&args.session_args).into(); + + insert_json5_option(&mut config, "plugins/ros2dds/id", &args.id); + insert_json5_option(&mut config, "plugins/ros2dds/namespace", &args.namespace); + insert_json5(&mut config, "plugins/ros2dds/domain", &args.domain); + insert_json5( + &mut config, + "plugins/ros2dds/ros_localhost_only", + &args.ros_localhost_only, + ); + #[cfg(feature = "dds_shm")] + { + insert_json5( + &mut config, + "plugins/ros2dds/shm_enabled", + &args.dds_enable_shm, + ); + } + insert_json5_list( + &mut config, + "plugins/ros2dds/pub_max_frequencies", + &args.pub_max_frequency, + ); + insert_json5_option( + &mut config, + "plugins/ros2dds/queries_timeout/default", + &args.queries_timeout_default, + ); + + insert_json5_option(&mut config, "plugins/rest/http_port", &args.rest_http_port); + + config + } +} + +fn insert_json5(config: &mut Config, key: &str, value: &T) +where + T: Sized + serde::Serialize, +{ + config + .insert_json5(key, &serde_json::to_string(value).unwrap()) + .unwrap(); +} + +fn insert_json5_option(config: &mut Config, key: &str, value: &Option) +where + T: Sized + serde::Serialize, +{ + if let Some(v) = value { + config + .insert_json5(key, &serde_json::to_string(v).unwrap()) + .unwrap(); + } +} + +fn insert_json5_list(config: &mut Config, key: &str, values: &Vec) +where + T: Sized + serde::Serialize, +{ + if !values.is_empty() { + config + .insert_json5(key, &serde_json::to_string(values).unwrap()) + .unwrap(); + } +} diff --git a/zenoh-bridge-ros2dds/src/main.rs b/zenoh-bridge-ros2dds/src/main.rs index 155f6f1..a53a0ce 100644 --- a/zenoh-bridge-ros2dds/src/main.rs +++ b/zenoh-bridge-ros2dds/src/main.rs @@ -12,184 +12,17 @@ // ZettaScale Zenoh Team, // use async_liveliness_monitor::LivelinessMonitor; -use clap::{App, Arg}; +use bridge_args::BridgeArgs; +use clap::Parser; use std::time::{Duration, SystemTime}; -use zenoh::config::{Config, ModeDependentValue}; -use zenoh::prelude::*; +use zenoh::config::Config; -lazy_static::lazy_static!( - pub static ref DEFAULT_DOMAIN_STR: String = zenoh_plugin_ros2dds::config::DEFAULT_DOMAIN.to_string(); -); +mod bridge_args; +mod zenoh_args; -macro_rules! insert_json5 { - ($config: expr, $args: expr, $key: expr, if $name: expr) => { - if $args.occurrences_of($name) > 0 { - $config.insert_json5($key, "true").unwrap(); - } - }; - ($config: expr, $args: expr, $key: expr, if $name: expr, $($t: tt)*) => { - if $args.occurrences_of($name) > 0 { - $config.insert_json5($key, &serde_json::to_string(&$args.value_of($name).unwrap()$($t)*).unwrap()).unwrap(); - } - }; - ($config: expr, $args: expr, $key: expr, for $name: expr, $($t: tt)*) => { - if let Some(value) = $args.values_of($name) { - $config.insert_json5($key, &serde_json::to_string(&value$($t)*).unwrap()).unwrap(); - } - }; -} - -fn parse_args() -> (Config, Option) { - let mut app = App::new("zenoh bridge for DDS") - .version(zenoh_plugin_ros2dds::GIT_VERSION) - .long_version(zenoh_plugin_ros2dds::LONG_VERSION.as_str()) - // - // zenoh related arguments: - // - .arg(Arg::from_usage( -r"-i, --id=[HEX_STRING] \ -'The identifier (as an hexadecimal string, with odd number of chars - e.g.: 0A0B23...) that zenohd must use. -WARNING: this identifier must be unique in the system and must be 16 bytes maximum (32 chars)! -If not set, a random UUIDv4 will be used.'" - )) - .arg(Arg::from_usage( -r"-m, --mode=[MODE] 'The zenoh session mode.'") - .possible_values(["peer", "client"]) - .default_value("peer") - ) - .arg(Arg::from_usage( -r"-c, --config=[FILE] \ -'The configuration file. Currently, this file must be a valid JSON5 file.'" - )) - .arg(Arg::from_usage( -r"-l, --listen=[ENDPOINT]... \ -'A locator on which this router will listen for incoming sessions. -Repeat this option to open several listeners.'" - ), - ) - .arg(Arg::from_usage( -r"-e, --connect=[ENDPOINT]... \ -'A peer locator this router will try to connect to. -Repeat this option to connect to several peers.'" - )) - .arg(Arg::from_usage( -r"--no-multicast-scouting \ -'By default the zenoh bridge listens and replies to UDP multicast scouting messages for being discovered by peers and routers. -This option disables this feature.'" - )) - .arg(Arg::from_usage( -r"--rest-http-port=[PORT | IP:PORT] \ -'Configures HTTP interface for the REST API (disabled by default, setting this option enables it). Accepted values:' - - a port number - - a string with format `:` (to bind the HTTP server to a specific interface)." - )) - // - // DDS related arguments: - // - .arg(Arg::from_usage( -r#"-n, --namespace=[String] 'A ROS 2 namespace to be used by the "zenoh_bridge_dds" node'"# - )) - .arg(Arg::from_usage( -r#"-d, --domain=[ID] 'The DDS Domain ID. The default value is "$ROS_DOMAIN_ID" if defined, or "0" otherwise.'"#) - .default_value(&DEFAULT_DOMAIN_STR) - ) - .arg(Arg::from_usage( -r#"--ros-localhost-only \ -'Configure CycloneDDS to use only the localhost interface. If not set, CycloneDDS will pick the interface defined in "$CYCLONEDDS_URI" configuration, or automatically choose one. -This option is not active by default, unless the "ROS_LOCALHOST_ONLY" environment variable is set to "1".'"# - )); - - // Add option to enable DDS SHM if feature is enabled - #[cfg(feature = "dds_shm")] - { - app = app.arg(Arg::from_usage( - r#"--dds-enable-shm \ - 'Configure CycloneDDS to use Iceoryx shared memory. If not set, CycloneDDS will instead use any shared memory settings defined in "$CYCLONEDDS_URI" configuration. - This option is not active by default.'"# - )); - } - - app = app - .arg(Arg::from_usage( -r#"--pub-max-frequency=[String]... 'Specifies a maximum frequency of publications routing over zenoh for a set of Publishers. - The string must have the format "=": - - "regex" is a regular expression matching a Publisher interface name - - "float" is the maximum frequency in Hertz; if publication rate is higher, downsampling will occur when routing. -Repeat this option to configure several topics expressions with a max frequency.'"# - )) - .arg(Arg::from_usage( -r#"--queries-timeout-default=[float]... 'A float in seconds (default: 5.0 sec) that will be used as a timeout when the bridge -queries any other remote bridge for discovery information and for historical data for TRANSIENT_LOCAL DDS Readers it serves -(i.e. if the query to the remote bridge exceed the timeout, some historical samples might be not routed to the Readers, but the route will not be blocked forever). -This value overwrites the value possibly set in configuration file under 'plugins/ros2dds/queries_timeout/default' key."# - )) - .arg(Arg::from_usage( -r#"--watchdog=[PERIOD] 'Experimental!! Run a watchdog thread that monitors the bridge's async executor and reports as error log any stalled status during the specified period (default: 1.0 second)'"# - ).default_missing_value("1.0")); - let args = app.get_matches(); - - // load config file at first - let mut config = match args.value_of("config") { - Some(conf_file) => Config::from_file(conf_file).unwrap(), - None => Config::default(), - }; - // if "ros2dds" plugin conf is not present, add it (empty to use default config) - if config.plugin("ros2dds").is_none() { - config.insert_json5("plugins/ros2dds", "{}").unwrap(); - } - - // apply zenoh related arguments over config - // NOTE: only if args.occurrences_of()>0 to avoid overriding config with the default arg value - if args.occurrences_of("mode") > 0 { - config - .set_mode(Some(args.value_of("mode").unwrap().parse().unwrap())) - .unwrap(); - } - if let Some(endpoints) = args.values_of("connect") { - config - .connect - .endpoints - .extend(endpoints.map(|p| p.parse().unwrap())) - } - if let Some(endpoints) = args.values_of("listen") { - config - .listen - .endpoints - .extend(endpoints.map(|p| p.parse().unwrap())) - } - if args.is_present("no-multicast-scouting") { - config.scouting.multicast.set_enabled(Some(false)).unwrap(); - } - if let Some(port) = args.value_of("rest-http-port") { - config - .insert_json5("plugins/rest/http_port", &format!(r#""{port}""#)) - .unwrap(); - } - // Always add timestamps to publications (required for PublicationCache used in case of TRANSIENT_LOCAL topics) - config - .timestamping - .set_enabled(Some(ModeDependentValue::Unique(true))) - .unwrap(); - - // apply DDS related arguments over config - insert_json5!(config, args, "plugins/ros2dds/id", if "id",); - insert_json5!(config, args, "plugins/ros2dds/namespace", if "namespace",); - insert_json5!(config, args, "plugins/ros2dds/domain", if "domain", .parse::().unwrap()); - insert_json5!(config, args, "plugins/ros2dds/ros_localhost_only", if "ros-localhost-only"); - #[cfg(feature = "dds_shm")] - { - insert_json5!(config, args, "plugins/ros2dds/shm_enabled", if "dds-enable-shm"); - } - insert_json5!(config, args, "plugins/ros2dds/pub_max_frequencies", for "pub-max-frequency", .collect::>()); - insert_json5!(config, args, "plugins/ros2dds/queries_timeout/default", if "queries-timeout-default", .parse::().unwrap()); - - let watchdog_period = if args.is_present("watchdog") { - args.value_of("watchdog").map(|s| s.parse::().unwrap()) - } else { - None - }; - - (config, watchdog_period) +fn parse_args() -> (Option, Config) { + let args = BridgeArgs::parse(); + (args.watchdog.flatten(), args.into()) } #[async_std::main] @@ -200,7 +33,7 @@ async fn main() { *zenoh_plugin_ros2dds::LONG_VERSION ); - let (config, watchdog_period) = parse_args(); + let (watchdog_period, config) = parse_args(); let rest_plugin = config.plugin("rest").is_some(); if let Some(period) = watchdog_period { diff --git a/zenoh-bridge-ros2dds/src/zenoh_args.rs b/zenoh-bridge-ros2dds/src/zenoh_args.rs new file mode 100644 index 0000000..e0999f2 --- /dev/null +++ b/zenoh-bridge-ros2dds/src/zenoh_args.rs @@ -0,0 +1,90 @@ +// +// Copyright (c) 2022 ZettaScale Technology +// +// This program and the accompanying materials are made available under the +// terms of the Eclipse Public License 2.0 which is available at +// http://www.eclipse.org/legal/epl-2.0, or the Apache License, Version 2.0 +// which is available at https://www.apache.org/licenses/LICENSE-2.0. +// +// SPDX-License-Identifier: EPL-2.0 OR Apache-2.0 +// +// Contributors: +// ZettaScale Zenoh Team, +// + +//! Copied from https://github.com/eclipse-zenoh/zenoh/blob/master/examples/src/lib.rs +//! Usual command line arguments to manage a Zenoh Config + +use zenoh::config::Config; + +#[derive(clap::ValueEnum, Clone, Copy, PartialEq, Eq, Hash, Debug)] +pub enum Wai { + Peer, + Client, + Router, +} +impl core::fmt::Display for Wai { + fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result { + core::fmt::Debug::fmt(&self, f) + } +} +#[derive(clap::Parser, Clone, PartialEq, Eq, Hash, Debug)] +pub struct CommonArgs { + #[arg(short, long)] + /// A configuration file. + pub config: Option, + #[arg(short, long, default_value = "peer")] + /// The Zenoh session mode. + pub mode: Wai, + #[arg(short = 'e', long)] + /// Endpoints to connect to. + pub connect: Vec, + #[arg(short, long)] + /// Endpoints to listen on. + pub listen: Vec, + #[arg(long)] + /// Disable the multicast-based scouting mechanism. + pub no_multicast_scouting: bool, + #[arg(long)] + /// Disable the multicast-based scouting mechanism. + pub enable_shm: bool, +} + +impl From for Config { + fn from(value: CommonArgs) -> Self { + (&value).into() + } +} +impl From<&CommonArgs> for Config { + fn from(value: &CommonArgs) -> Self { + let mut config = match &value.config { + Some(path) => Config::from_file(path).unwrap(), + None => Config::default(), + }; + match value.mode { + Wai::Peer => config.set_mode(Some(zenoh::scouting::WhatAmI::Peer)), + Wai::Client => config.set_mode(Some(zenoh::scouting::WhatAmI::Client)), + Wai::Router => config.set_mode(Some(zenoh::scouting::WhatAmI::Router)), + } + .unwrap(); + if !value.connect.is_empty() { + config.connect.endpoints = value.connect.iter().map(|v| v.parse().unwrap()).collect(); + } + if !value.listen.is_empty() { + config.listen.endpoints = value.listen.iter().map(|v| v.parse().unwrap()).collect(); + } + if value.no_multicast_scouting { + config.scouting.multicast.set_enabled(Some(false)).unwrap(); + } + if value.enable_shm { + #[cfg(feature = "shared-memory")] + config.transport.shared_memory.set_enabled(true).unwrap(); + #[cfg(not(feature = "shared-memory"))] + { + println!("enable-shm argument: SHM cannot be enabled, because Zenoh is compiled without shared-memory feature!"); + std::process::exit(-1); + } + } + config + } +}