From d96c903df87b02b96aaf741685fbed005805de72 Mon Sep 17 00:00:00 2001 From: gabrik Date: Wed, 3 Apr 2024 14:34:15 +0200 Subject: [PATCH 1/3] feat(tracing): using tracing and zenoh-util init log Signed-off-by: gabrik --- Cargo.lock | 289 +++++++++++------- Cargo.toml | 17 +- zenoh-bridge-ros2dds/Cargo.toml | 4 +- zenoh-bridge-ros2dds/src/main.rs | 14 +- zenoh-bridge-ros2dds/src/ros_args.rs | 4 +- zenoh-plugin-ros2dds/Cargo.toml | 3 +- zenoh-plugin-ros2dds/src/dds_discovery.rs | 16 +- zenoh-plugin-ros2dds/src/dds_utils.rs | 2 +- .../src/discovered_entities.rs | 28 +- zenoh-plugin-ros2dds/src/discovery_mgr.rs | 14 +- zenoh-plugin-ros2dds/src/lib.rs | 56 ++-- zenoh-plugin-ros2dds/src/node_info.rs | 120 ++++---- zenoh-plugin-ros2dds/src/ros2_utils.rs | 6 +- zenoh-plugin-ros2dds/src/ros_discovery.rs | 16 +- zenoh-plugin-ros2dds/src/route_action_cli.rs | 14 +- zenoh-plugin-ros2dds/src/route_action_srv.rs | 14 +- zenoh-plugin-ros2dds/src/route_publisher.rs | 40 +-- zenoh-plugin-ros2dds/src/route_service_cli.rs | 62 ++-- zenoh-plugin-ros2dds/src/route_service_srv.rs | 44 +-- zenoh-plugin-ros2dds/src/route_subscriber.rs | 40 +-- zenoh-plugin-ros2dds/src/routes_mgr.rs | 44 +-- 21 files changed, 451 insertions(+), 396 deletions(-) diff --git a/Cargo.lock b/Cargo.lock index 4e86728..8ee714c 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -995,42 +995,6 @@ version = "1.9.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "a26ae43d7bcc3b814de94796a5e736d4029efb0ee900c12e2d54c993ad1a1e07" -[[package]] -name = "env_filter" -version = "0.1.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a009aa4810eb158359dda09d0c87378e4bbb89b5a801f016885a4707ba24f7ea" -dependencies = [ - "log", - "regex", -] - -[[package]] -name = "env_logger" -version = "0.10.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4cd405aab171cb85d6735e5c8d9db038c17d3ca007a4d2c25f337935c3d90580" -dependencies = [ - "humantime", - "is-terminal", - "log", - "regex", - "termcolor", -] - -[[package]] -name = "env_logger" -version = "0.11.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6c012a26a7f605efc424dd53697843a72be7dc86ad2d01f7814337794a12231d" -dependencies = [ - "anstream", - "anstyle", - "env_filter", - "humantime", - "log", -] - [[package]] name = "equivalent" version = "1.0.1" @@ -1585,17 +1549,6 @@ dependencies = [ "serde", ] -[[package]] -name = "is-terminal" -version = "0.4.9" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "cb0889898416213fab133e1d33a0e5858a48177452750691bde3666d0fdbaf8b" -dependencies = [ - "hermit-abi", - "rustix 0.38.13", - "windows-sys 0.48.0", -] - [[package]] name = "iso8601" version = "0.6.1" @@ -1764,6 +1717,15 @@ dependencies = [ "twox-hash", ] +[[package]] +name = "matchers" +version = "0.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8263075bb86c5a1b1427b5ae862e8889656f126e9f77c484496e8b47cf5c5558" +dependencies = [ + "regex-automata 0.1.10", +] + [[package]] name = "memchr" version = "2.6.3" @@ -1832,6 +1794,16 @@ dependencies = [ "minimal-lexical", ] +[[package]] +name = "nu-ansi-term" +version = "0.46.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "77a8165726e8236064dbb45459242600304b42a5ea24ee2948e18e023bf7ba84" +dependencies = [ + "overload", + "winapi", +] + [[package]] name = "num" version = "0.4.1" @@ -1984,6 +1956,12 @@ dependencies = [ "num-traits", ] +[[package]] +name = "overload" +version = "0.1.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b15813163c1d831bf4a13c3610c05c0d03b39feb07f7e09fa234dac9b15aaf39" + [[package]] name = "parking" version = "2.1.0" @@ -2409,8 +2387,17 @@ checksum = "697061221ea1b4a94a624f67d0ae2bfe4e22b8a17b6a192afb11046542cc8c47" dependencies = [ "aho-corasick", "memchr", - "regex-automata", - "regex-syntax", + "regex-automata 0.3.8", + "regex-syntax 0.7.5", +] + +[[package]] +name = "regex-automata" +version = "0.1.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6c230d73fb8d8c1b9c0b3135c5142a8acee3a0558fb8db5cf1cb65f8d7862132" +dependencies = [ + "regex-syntax 0.6.29", ] [[package]] @@ -2421,9 +2408,15 @@ checksum = "c2f401f4955220693b56f8ec66ee9c78abffd8d1c4f23dc41a23839eb88f0795" dependencies = [ "aho-corasick", "memchr", - "regex-syntax", + "regex-syntax 0.7.5", ] +[[package]] +name = "regex-syntax" +version = "0.6.29" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f162c6dd7b008981e4d40210aca20b4bd0f9b60ca9271061b07f78537722f2e1" + [[package]] name = "regex-syntax" version = "0.7.5" @@ -2907,6 +2900,15 @@ dependencies = [ "keccak", ] +[[package]] +name = "sharded-slab" +version = "0.1.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f40ca3c46823713e0d4209592e8d6e826aa57e928f09752619fc696c499637f6" +dependencies = [ + "lazy_static", +] + [[package]] name = "shellexpand" version = "3.1.0" @@ -3198,15 +3200,6 @@ dependencies = [ "unicode-ident", ] -[[package]] -name = "termcolor" -version = "1.4.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "06794f8f6c5c898b3275aebefa6b8a1cb24cd2c6c79397ab15774837a0bc5755" -dependencies = [ - "winapi-util", -] - [[package]] name = "thiserror" version = "1.0.48" @@ -3227,6 +3220,16 @@ dependencies = [ "syn 2.0.55", ] +[[package]] +name = "thread_local" +version = "1.1.8" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8b9ef9bad013ada3808854ceac7b46812a6465ba368859a37e2100283d2d719c" +dependencies = [ + "cfg-if 1.0.0", + "once_cell", +] + [[package]] name = "tide" version = "0.16.0" @@ -3446,6 +3449,49 @@ source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "0955b8137a1df6f1a2e9a37d8a6656291ff0297c1a97c24e0d8425fe2312f79a" dependencies = [ "once_cell", + "valuable", +] + +[[package]] +name = "tracing-log" +version = "0.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ee855f1f400bd0e5c02d150ae5de3840039a3f54b025156404e34c23c03f47c3" +dependencies = [ + "log", + "once_cell", + "tracing-core", +] + +[[package]] +name = "tracing-serde" +version = "0.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bc6b213177105856957181934e4920de57730fc69bf42c37ee5bb664d406d9e1" +dependencies = [ + "serde", + "tracing-core", +] + +[[package]] +name = "tracing-subscriber" +version = "0.3.18" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ad0f048c97dbd9faa9b7df56362b8ebcaa52adb06b498c050d2f4e32f90a7a8b" +dependencies = [ + "matchers", + "nu-ansi-term", + "once_cell", + "regex", + "serde", + "serde_json", + "sharded-slab", + "smallvec", + "thread_local", + "tracing", + "tracing-core", + "tracing-log", + "tracing-serde", ] [[package]] @@ -3626,6 +3672,12 @@ dependencies = [ "unzip-n", ] +[[package]] +name = "valuable" +version = "0.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "830b7e5d4d90034032940e4ace0d9a9a057e7a45cd94e6c007832e39edb82f6d" + [[package]] name = "value-bag" version = "1.4.1" @@ -3807,15 +3859,6 @@ version = "0.4.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "ac3b87c63620426dd9b991e5ce0329eff545bccbbb34f3be09ff6fb6ab51b7b6" -[[package]] -name = "winapi-util" -version = "0.1.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "70ec6ce85bb158151cae5e5c87f95a8e97d2c0c4b001223f33a334e3ce5de178" -dependencies = [ - "winapi", -] - [[package]] name = "winapi-x86_64-pc-windows-gnu" version = "0.4.0" @@ -3966,19 +4009,17 @@ checksum = "dff9641d1cd4be8d1a070daf9e3773c5f67e78b4d9d42263020c057706765c04" [[package]] name = "zenoh" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-trait", "base64 0.21.4", "const_format", - "env_logger 0.11.2", "event-listener 4.0.0", "flume", "form_urlencoded", "futures", "git-version", "lazy_static", - "log", "ordered-float", "paste", "petgraph", @@ -3991,6 +4032,7 @@ dependencies = [ "stop-token", "tokio", "tokio-util", + "tracing", "uhlc", "uuid", "vec_map", @@ -4008,6 +4050,7 @@ dependencies = [ "zenoh-result", "zenoh-runtime", "zenoh-sync", + "zenoh-task", "zenoh-transport", "zenoh-util", ] @@ -4019,21 +4062,21 @@ dependencies = [ "async-liveliness-monitor", "async-std", "clap", - "env_logger 0.10.2", "lazy_static", - "log", "serde", "serde_json", + "tracing", "zenoh", "zenoh-plugin-rest", "zenoh-plugin-ros2dds", "zenoh-plugin-trait", + "zenoh-util", ] [[package]] name = "zenoh-buffers" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "zenoh-collections", ] @@ -4041,10 +4084,10 @@ dependencies = [ [[package]] name = "zenoh-codec" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ - "log", "serde", + "tracing", "uhlc", "zenoh-buffers", "zenoh-protocol", @@ -4053,21 +4096,21 @@ dependencies = [ [[package]] name = "zenoh-collections" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" [[package]] name = "zenoh-config" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "flume", "json5", - "log", "num_cpus", "secrecy", "serde", "serde_json", "serde_yaml", + "tracing", "validated_struct", "zenoh-core", "zenoh-protocol", @@ -4078,7 +4121,7 @@ dependencies = [ [[package]] name = "zenoh-core" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-global-executor", "lazy_static", @@ -4090,7 +4133,7 @@ dependencies = [ [[package]] name = "zenoh-crypto" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "aes 0.8.3", "hmac 0.12.1", @@ -4103,28 +4146,28 @@ dependencies = [ [[package]] name = "zenoh-ext" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "bincode", - "env_logger 0.11.2", "flume", "futures", - "log", "serde", "tokio", + "tracing", "zenoh", "zenoh-core", "zenoh-macros", "zenoh-result", "zenoh-runtime", "zenoh-sync", + "zenoh-task", "zenoh-util", ] [[package]] name = "zenoh-keyexpr" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "hashbrown 0.14.0", "keyed-set", @@ -4138,7 +4181,7 @@ dependencies = [ [[package]] name = "zenoh-link" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-trait", "zenoh-config", @@ -4156,17 +4199,17 @@ dependencies = [ [[package]] name = "zenoh-link-commons" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-trait", "flume", "futures", - "log", "rustls 0.22.2", "rustls-webpki 0.102.2", "serde", "tokio", "tokio-util", + "tracing", "zenoh-buffers", "zenoh-codec", "zenoh-core", @@ -4179,12 +4222,11 @@ dependencies = [ [[package]] name = "zenoh-link-quic" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-trait", "base64 0.21.4", "futures", - "log", "quinn", "rustls 0.21.7", "rustls-native-certs 0.7.0", @@ -4194,6 +4236,7 @@ dependencies = [ "tokio", "tokio-rustls 0.24.1", "tokio-util", + "tracing", "zenoh-config", "zenoh-core", "zenoh-link-commons", @@ -4207,12 +4250,12 @@ dependencies = [ [[package]] name = "zenoh-link-tcp" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-trait", - "log", "tokio", "tokio-util", + "tracing", "zenoh-core", "zenoh-link-commons", "zenoh-protocol", @@ -4225,12 +4268,11 @@ dependencies = [ [[package]] name = "zenoh-link-tls" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-trait", "base64 0.21.4", "futures", - "log", "rustls 0.22.2", "rustls-pemfile 2.0.0", "rustls-pki-types", @@ -4239,6 +4281,7 @@ dependencies = [ "tokio", "tokio-rustls 0.25.0", "tokio-util", + "tracing", "webpki-roots", "zenoh-config", "zenoh-core", @@ -4253,13 +4296,13 @@ dependencies = [ [[package]] name = "zenoh-link-udp" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-trait", - "log", "socket2 0.5.6", "tokio", "tokio-util", + "tracing", "zenoh-buffers", "zenoh-collections", "zenoh-core", @@ -4274,14 +4317,14 @@ dependencies = [ [[package]] name = "zenoh-link-unixsock_stream" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-trait", "futures", - "log", "nix", "tokio", "tokio-util", + "tracing", "uuid", "zenoh-core", "zenoh-link-commons", @@ -4294,14 +4337,14 @@ dependencies = [ [[package]] name = "zenoh-link-ws" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-trait", "futures-util", - "log", "tokio", "tokio-tungstenite", "tokio-util", + "tracing", "url", "zenoh-core", "zenoh-link-commons", @@ -4315,7 +4358,7 @@ dependencies = [ [[package]] name = "zenoh-macros" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "proc-macro2", "quote", @@ -4326,25 +4369,24 @@ dependencies = [ [[package]] name = "zenoh-plugin-rest" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "anyhow", "async-std", "base64 0.21.4", "const_format", - "env_logger 0.11.2", "flume", "futures", "git-version", "http-types", "jsonschema", "lazy_static", - "log", "rustc_version 0.4.0", "schemars", "serde", "serde_json", "tide", + "tracing", "zenoh", "zenoh-plugin-trait", "zenoh-result", @@ -4361,17 +4403,16 @@ dependencies = [ "cdr", "cyclors", "derivative", - "env_logger 0.10.2", "flume", "futures", "git-version", "hex", "lazy_static", - "log", "regex", "rustc_version 0.4.0", "serde", "serde_json", + "tracing", "zenoh", "zenoh-collections", "zenoh-core", @@ -4383,13 +4424,13 @@ dependencies = [ [[package]] name = "zenoh-plugin-trait" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "const_format", "libloading", - "log", "serde", "serde_json", + "tracing", "zenoh-keyexpr", "zenoh-macros", "zenoh-result", @@ -4399,7 +4440,7 @@ dependencies = [ [[package]] name = "zenoh-protocol" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "const_format", "rand 0.8.5", @@ -4413,7 +4454,7 @@ dependencies = [ [[package]] name = "zenoh-result" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "anyhow", ] @@ -4421,8 +4462,9 @@ dependencies = [ [[package]] name = "zenoh-runtime" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ + "futures", "lazy_static", "tokio", "zenoh-collections", @@ -4432,7 +4474,7 @@ dependencies = [ [[package]] name = "zenoh-sync" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "event-listener 4.0.0", "futures", @@ -4443,14 +4485,26 @@ dependencies = [ "zenoh-runtime", ] +[[package]] +name = "zenoh-task" +version = "0.11.0-dev" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +dependencies = [ + "futures", + "tokio", + "tokio-util", + "tracing", + "zenoh-core", + "zenoh-runtime", +] + [[package]] name = "zenoh-transport" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-trait", "flume", - "log", "lz4_flex", "paste", "rand 0.8.5", @@ -4460,6 +4514,7 @@ dependencies = [ "sha3", "tokio", "tokio-util", + "tracing", "zenoh-buffers", "zenoh-codec", "zenoh-collections", @@ -4471,13 +4526,14 @@ dependencies = [ "zenoh-result", "zenoh-runtime", "zenoh-sync", + "zenoh-task", "zenoh-util", ] [[package]] name = "zenoh-util" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#e04c8613d3c33472edcbde6fde5bd4beeb24f2bf" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" dependencies = [ "async-std", "async-trait", @@ -4487,10 +4543,11 @@ dependencies = [ "lazy_static", "libc", "libloading", - "log", "pnet_datalink", "shellexpand", "tokio", + "tracing", + "tracing-subscriber", "winapi", "zenoh-core", "zenoh-result", diff --git a/Cargo.toml b/Cargo.toml index 2896e21..8da3eed 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -32,28 +32,27 @@ cdr = "0.2.4" clap = "4.4.11" cyclors = "0.2.0" derivative = "2.2.0" -env_logger = "0.10.0" flume = "0.11.0" futures = "0.3.26" git-version = "0.3.5" hex = "0.4.3" lazy_static = "1.4.0" -log = "0.4.17" regex = "1.7.1" rustc_version = "0.4" serde = "1.0.154" serde_json = "1.0.94" -zenoh = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", features = [ +tracing = "0.1" +zenoh = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing", features = [ "unstable", ] } -zenoh-collections = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main" } -zenoh-core = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main" } -zenoh-ext = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", features = [ +zenoh-collections = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing" } +zenoh-core = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing" } +zenoh-ext = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing", features = [ "unstable", ] } -zenoh-plugin-rest = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", default-features = false } -zenoh-plugin-trait = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", default-features = false } -zenoh-util = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", default-features = false } +zenoh-plugin-rest = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing", default-features = false } +zenoh-plugin-trait = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing", default-features = false } +zenoh-util = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing", default-features = false } [profile.release] debug = false diff --git a/zenoh-bridge-ros2dds/Cargo.toml b/zenoh-bridge-ros2dds/Cargo.toml index 266f2cd..7289263 100644 --- a/zenoh-bridge-ros2dds/Cargo.toml +++ b/zenoh-bridge-ros2dds/Cargo.toml @@ -29,15 +29,15 @@ dds_shm = ["zenoh-plugin-ros2dds/dds_shm"] async-std = { workspace = true, features = ["unstable", "attributes"] } async-liveliness-monitor = { 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 } +tracing = { workspace = true } zenoh = { workspace = true } zenoh-plugin-rest = { workspace = true } zenoh-plugin-trait = { workspace = true } zenoh-plugin-ros2dds = { version = "0.11.0-dev", path = "../zenoh-plugin-ros2dds/", default-features = false } +zenoh-util = { workspace = true } [[bin]] name = "zenoh-bridge-ros2dds" diff --git a/zenoh-bridge-ros2dds/src/main.rs b/zenoh-bridge-ros2dds/src/main.rs index d3998bc..ab9ddab 100644 --- a/zenoh-bridge-ros2dds/src/main.rs +++ b/zenoh-bridge-ros2dds/src/main.rs @@ -60,8 +60,8 @@ fn parse_args() -> (Option, Config) { #[async_std::main] async fn main() { - env_logger::Builder::from_env(env_logger::Env::default().default_filter_or("z=info")).init(); - log::info!( + zenoh_util::init_log(); + tracing::info!( "zenoh-bridge-ros2dds {}", zenoh_plugin_ros2dds::ROS2Plugin::PLUGIN_LONG_VERSION ); @@ -106,7 +106,7 @@ fn run_watchdog(period: f32) { // Start a Liveliness Monitor thread for async_std Runtime let (_task, monitor) = LivelinessMonitor::start(async_std::task::spawn); std::thread::spawn(move || { - log::debug!( + tracing::debug!( "Watchdog started with period {} sec", sleep_time.as_secs_f32() ); @@ -117,7 +117,7 @@ fn run_watchdog(period: f32) { // Monitor watchdog thread itself if elapsed > sleep_time + max_sleep_delta { - log::warn!( + tracing::warn!( "Watchdog thread slept more than configured: {} seconds", elapsed.as_secs_f32() ); @@ -126,11 +126,11 @@ fn run_watchdog(period: f32) { let report = monitor.latest_report(); if report.elapsed() > report_threshold_1 { if report.elapsed() > sleep_time { - log::error!("Watchdog detecting async_std is stalled! No task scheduling since {} seconds", report.elapsed().as_secs_f32()); + tracing::error!("Watchdog detecting async_std is stalled! No task scheduling since {} seconds", report.elapsed().as_secs_f32()); } else if report.elapsed() > report_threshold_2 { - log::warn!("Watchdog detecting async_std was not scheduling tasks during the last {} ms", report.elapsed().as_micros()); + tracing::warn!("Watchdog detecting async_std was not scheduling tasks during the last {} ms", report.elapsed().as_micros()); } else { - log::info!("Watchdog detecting async_std was not scheduling tasks during the last {} ms", report.elapsed().as_micros()); + tracing::info!("Watchdog detecting async_std was not scheduling tasks during the last {} ms", report.elapsed().as_micros()); } } } diff --git a/zenoh-bridge-ros2dds/src/ros_args.rs b/zenoh-bridge-ros2dds/src/ros_args.rs index 33d7d87..c23604d 100644 --- a/zenoh-bridge-ros2dds/src/ros_args.rs +++ b/zenoh-bridge-ros2dds/src/ros_args.rs @@ -58,14 +58,14 @@ impl RosArgs { for r in &self.remap { match r.from { RemapFrom::Namespace => { - log::info!( + tracing::info!( "Remapping namespace to '{}' as per ROS command line argument", r.to ); insert_json5(config, "plugins/ros2dds/namespace", &r.to); } RemapFrom::Node => { - log::info!( + tracing::info!( "Remapping node name to '{}' as per ROS command line argument", r.to ); diff --git a/zenoh-plugin-ros2dds/Cargo.toml b/zenoh-plugin-ros2dds/Cargo.toml index 32637df..a653b5d 100644 --- a/zenoh-plugin-ros2dds/Cargo.toml +++ b/zenoh-plugin-ros2dds/Cargo.toml @@ -39,16 +39,15 @@ bincode = { workspace = true } cdr = { workspace = true } cyclors = { workspace = true } derivative = { workspace = true } -env_logger = { workspace = true } flume = { workspace = true } futures = { workspace = true } git-version = { workspace = true } hex = { workspace = true } lazy_static = { workspace = true } -log = { workspace = true } regex = { workspace = true } serde = { workspace = true } serde_json = { workspace = true } +tracing = { workspace = true } zenoh = { workspace = true } zenoh-collections = { workspace = true } zenoh-core = { workspace = true } diff --git a/zenoh-plugin-ros2dds/src/dds_discovery.rs b/zenoh-plugin-ros2dds/src/dds_discovery.rs index abcd62c..80dafb5 100644 --- a/zenoh-plugin-ros2dds/src/dds_discovery.rs +++ b/zenoh-plugin-ros2dds/src/dds_discovery.rs @@ -108,12 +108,12 @@ unsafe extern "C" fn on_data(dr: dds_entity_t, arg: *mut std::os::raw::c_void) { let topic_name = match CStr::from_ptr((*sample).topic_name).to_str() { Ok(s) => s, Err(e) => { - log::warn!("Discovery of an invalid topic name: {}", e); + tracing::warn!("Discovery of an invalid topic name: {}", e); continue; } }; if topic_name.starts_with("DCPS") { - log::debug!( + tracing::debug!( "Ignoring discovery of {} ({} is a builtin topic)", key, topic_name @@ -124,14 +124,14 @@ unsafe extern "C" fn on_data(dr: dds_entity_t, arg: *mut std::os::raw::c_void) { let type_name = match CStr::from_ptr((*sample).type_name).to_str() { Ok(s) => s, Err(e) => { - log::warn!("Discovery of an invalid topic type: {}", e); + tracing::warn!("Discovery of an invalid topic type: {}", e); continue; } }; let participant_key = (*sample).participant_key.v.into(); let keyless = (*sample).key.v[15] == 3 || (*sample).key.v[15] == 4; - log::debug!( + tracing::debug!( "Discovered DDS {} {} from Participant {} on {} with type {} (keyless: {})", discovery_type, key, @@ -148,7 +148,7 @@ unsafe extern "C" fn on_data(dr: dds_entity_t, arg: *mut std::os::raw::c_void) { 0 => match type_info.is_null() { false => Some(Arc::new(TypeInfo::new(type_info))), true => { - log::trace!( + tracing::trace!( "Type information not available for type {}", type_name ); @@ -156,7 +156,7 @@ unsafe extern "C" fn on_data(dr: dds_entity_t, arg: *mut std::os::raw::c_void) { } }, _ => { - log::warn!( + tracing::warn!( "Failed to lookup type information({})", CStr::from_ptr(dds_strretcode(ret)) .to_str() @@ -215,7 +215,7 @@ unsafe extern "C" fn on_data(dr: dds_entity_t, arg: *mut std::os::raw::c_void) { } if is_alive { - log::debug!("Discovered DDS Participant {})", key,); + tracing::debug!("Discovered DDS Participant {})", key,); // Send a DDSDiscoveryEvent let entity = DdsParticipant { @@ -242,7 +242,7 @@ unsafe extern "C" fn on_data(dr: dds_entity_t, arg: *mut std::os::raw::c_void) { fn send_discovery_event(sender: &Sender, event: DDSDiscoveryEvent) { if let Err(e) = sender.try_send(event) { - log::error!( + tracing::error!( "INTERNAL ERROR sending DDSDiscoveryEvent to internal channel: {:?}", e ); diff --git a/zenoh-plugin-ros2dds/src/dds_utils.rs b/zenoh-plugin-ros2dds/src/dds_utils.rs index 4a69f69..821872c 100644 --- a/zenoh-plugin-ros2dds/src/dds_utils.rs +++ b/zenoh-plugin-ros2dds/src/dds_utils.rs @@ -296,7 +296,7 @@ where if reader >= 0 { let res = dds_reader_wait_for_historical_data(reader, qos::DDS_100MS_DURATION); if res < 0 { - log::error!( + tracing::error!( "Error calling dds_reader_wait_for_historical_data(): {}", CStr::from_ptr(dds_strretcode(-res)) .to_str() diff --git a/zenoh-plugin-ros2dds/src/discovered_entities.rs b/zenoh-plugin-ros2dds/src/discovered_entities.rs index fbc7a30..9b6c377 100644 --- a/zenoh-plugin-ros2dds/src/discovered_entities.rs +++ b/zenoh-plugin-ros2dds/src/discovered_entities.rs @@ -98,7 +98,7 @@ impl DiscoveredEntities { // Remove associated NodeInfos if let Some(nodes) = self.nodes_info.remove(gid) { for (name, mut node) in nodes { - log::info!("Undiscovered ROS Node {}", name); + tracing::info!("Undiscovered ROS Node {}", name); self.admin_space.remove( &zenoh::keformat!(ke_admin_node::formatter(), node_id = node.id_as_keyexpr(),) .unwrap(), @@ -267,7 +267,7 @@ impl DiscoveredEntities { // Remove nodes that are no longer present in ParticipantEntitiesInfo nodes_map.retain(|name, node| { if !ros_info.node_entities_info_seq.contains_key(name) { - log::info!("Undiscovered ROS Node {}", name); + tracing::info!("Undiscovered ROS Node {}", name); admin_space.remove( &zenoh::keformat!(ke_admin_node::formatter(), node_id = node.id_as_keyexpr(),) .unwrap(), @@ -284,7 +284,7 @@ impl DiscoveredEntities { for (name, ros_node_info) in &ros_info.node_entities_info_seq { // If node was not yet discovered, add a new NodeInfo if !nodes_map.contains_key(name) { - log::info!("Discovered ROS Node {}", name); + tracing::info!("Discovered ROS Node {}", name); match NodeInfo::create( ros_node_info.node_namespace.clone(), ros_node_info.node_name.clone(), @@ -302,7 +302,7 @@ impl DiscoveredEntities { nodes_map.insert(node.fullname().to_string(), node); } Err(e) => { - log::warn!("ROS Node has incompatible name: {e}"); + tracing::warn!("ROS Node has incompatible name: {e}"); break; } } @@ -333,19 +333,19 @@ impl DiscoveredEntities { // For each declared Reader for rgid in &ros_node_info.reader_gid_seq { if let Some(entity) = readers.get(rgid) { - log::trace!( + tracing::trace!( "ROS Node {ros_node_info} declares a Reader on {}", entity.topic_name ); if let Some(e) = node.update_with_reader(entity) { - log::debug!( + tracing::debug!( "ROS Node {ros_node_info} declares a new Reader on {}", entity.topic_name ); events.push(e) }; } else { - log::debug!( + tracing::debug!( "ROS Node {ros_node_info} declares a not yet discovered DDS Reader: {rgid}" ); node.undiscovered_reader.push(*rgid); @@ -354,19 +354,19 @@ impl DiscoveredEntities { // For each declared Writer for wgid in &ros_node_info.writer_gid_seq { if let Some(entity) = writers.get(wgid) { - log::trace!( + tracing::trace!( "ROS Node {ros_node_info} declares Writer on {}", entity.topic_name ); if let Some(e) = node.update_with_writer(entity) { - log::debug!( + tracing::debug!( "ROS Node {ros_node_info} declares a new Writer on {}", entity.topic_name ); events.push(e) }; } else { - log::debug!( + tracing::debug!( "ROS Node {ros_node_info} declares a not yet discovered DDS Writer: {wgid}" ); node.undiscovered_writer.push(*wgid); @@ -414,7 +414,7 @@ impl DiscoveredEntities { // the selector, if those keys had the admin_keyexpr_prefix. let sub_kes = selector.key_expr.strip_prefix(admin_keyexpr_prefix); if sub_kes.is_empty() { - log::error!("Received query for admin space: '{}' - but it's not prefixed by admin_keyexpr_prefix='{}'", selector, admin_keyexpr_prefix); + tracing::error!("Received query for admin space: '{}' - but it's not prefixed by admin_keyexpr_prefix='{}'", selector, admin_keyexpr_prefix); return; } @@ -453,12 +453,12 @@ impl DiscoveredEntities { .res_async() .await { - log::warn!("Error replying to admin query {:?}: {}", query, e); + tracing::warn!("Error replying to admin query {:?}: {}", query, e); } } - Ok(None) => log::error!("INTERNAL ERROR: Dangling {:?} for {}", entity_ref, key_expr), + Ok(None) => tracing::error!("INTERNAL ERROR: Dangling {:?} for {}", entity_ref, key_expr), Err(e) => { - log::error!("INTERNAL ERROR serializing admin value as JSON: {}", e) + tracing::error!("INTERNAL ERROR serializing admin value as JSON: {}", e) } } } diff --git a/zenoh-plugin-ros2dds/src/discovery_mgr.rs b/zenoh-plugin-ros2dds/src/discovery_mgr.rs index 3b6351e..d52737f 100644 --- a/zenoh-plugin-ros2dds/src/discovery_mgr.rs +++ b/zenoh-plugin-ros2dds/src/discovery_mgr.rs @@ -81,7 +81,7 @@ impl DiscoveryMgr { let evts = zwrite!(discovered_entities).remove_participant(&key); for e in evts { if let Err(err) = evt_sender.try_send(e) { - log::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); + tracing::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); } } }, @@ -89,7 +89,7 @@ impl DiscoveryMgr { let e = zwrite!(discovered_entities).add_writer(entity); if let Some(e) = e { if let Err(err) = evt_sender.try_send(e) { - log::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); + tracing::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); } } }, @@ -97,7 +97,7 @@ impl DiscoveryMgr { let e = zwrite!(discovered_entities).remove_writer(&key); if let Some(e) = e { if let Err(err) = evt_sender.try_send(e) { - log::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); + tracing::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); } } }, @@ -105,7 +105,7 @@ impl DiscoveryMgr { let e = zwrite!(discovered_entities).add_reader(entity); if let Some(e) = e { if let Err(err) = evt_sender.try_send(e) { - log::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); + tracing::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); } } }, @@ -113,7 +113,7 @@ impl DiscoveryMgr { let e = zwrite!(discovered_entities).remove_reader(&key); if let Some(e) = e { if let Err(err) = evt_sender.try_send(e) { - log::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); + tracing::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); } } }, @@ -123,11 +123,11 @@ impl DiscoveryMgr { _ = ros_disco_timer_rcv.recv_async() => { let infos = ros_discovery_mgr.read(); for part_info in infos { - log::debug!("Received ros_discovery_info from {}", part_info); + tracing::debug!("Received ros_discovery_info from {}", part_info); let evts = zwrite!(discovered_entities).update_participant_info(part_info); for e in evts { if let Err(err) = evt_sender.try_send(e) { - log::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); + tracing::error!("Internal error: failed to send DDSDiscoveryEvent to main loop: {err}"); } } } diff --git a/zenoh-plugin-ros2dds/src/lib.rs b/zenoh-plugin-ros2dds/src/lib.rs index a4a1907..8bc07a8 100644 --- a/zenoh-plugin-ros2dds/src/lib.rs +++ b/zenoh-plugin-ros2dds/src/lib.rs @@ -122,7 +122,7 @@ impl Plugin for ROS2Plugin { // Try to initiate login. // Required in case of dynamic lib, otherwise no logs. // But cannot be done twice in case of static link. - let _ = env_logger::try_init(); + zenoh_util::init_log(); let runtime_conf = runtime.config().lock(); let plugin_conf = runtime_conf @@ -141,16 +141,16 @@ pub async fn run(runtime: Runtime, config: Config) { // Try to initiate login. // Required in case of dynamic lib, otherwise no logs. // But cannot be done twice in case of static link. - let _ = env_logger::try_init(); - log::debug!("ROS2 plugin {}", ROS2Plugin::PLUGIN_VERSION); - log::info!("ROS2 plugin {:?}", config); + zenoh_util::init_log(); + tracing::debug!("ROS2 plugin {}", ROS2Plugin::PLUGIN_VERSION); + tracing::info!("ROS2 plugin {:?}", config); // Check config validity if !regex::Regex::new("/[A-Za-z0-9_/]*") .unwrap() .is_match(&config.namespace) { - log::error!( + tracing::error!( r#"Configuration error: invalid namespace "{}" must contain only alphanumeric, '_' or '/' characters and start with '/'"#, config.namespace ); @@ -160,7 +160,7 @@ pub async fn run(runtime: Runtime, config: Config) { .unwrap() .is_match(&config.nodename) { - log::error!( + tracing::error!( r#"Configuration error: invalid nodename "{}" must contain only alphanumeric or '_' characters"#, config.nodename ); @@ -171,14 +171,14 @@ pub async fn run(runtime: Runtime, config: Config) { let zsession = match zenoh::init(runtime).res_async().await { Ok(session) => Arc::new(session), Err(e) => { - log::error!("Unable to init zenoh session for DDS plugin : {:?}", e); + tracing::error!("Unable to init zenoh session for DDS plugin : {:?}", e); return; } }; let plugin_id = if let Some(ref id) = config.id { if id.contains('/') { - log::error!("The 'id' configuration must not contain any '/' character"); + tracing::error!("The 'id' configuration must not contain any '/' character"); return; } id.clone() @@ -197,7 +197,7 @@ pub async fn run(runtime: Runtime, config: Config) { { Ok(member) => member, Err(e) => { - log::error!( + tracing::error!( "Unable to declare liveliness token for DDS plugin : {:?}", e ); @@ -233,14 +233,14 @@ pub async fn run(runtime: Runtime, config: Config) { } // create DDS Participant - log::debug!( + tracing::debug!( "Create DDS Participant on domain {} with CYCLONEDDS_URI='{}'", config.domain, env::var("CYCLONEDDS_URI").unwrap_or_default() ); let participant = unsafe { dds_create_participant(config.domain, std::ptr::null(), std::ptr::null()) }; - log::debug!( + tracing::debug!( "ROS2 plugin {} using DDS Participant {} created", plugin_id, get_guid(&participant).unwrap() @@ -301,7 +301,7 @@ impl<'a> ROS2PluginRuntime<'a> { let admin_prefix = zenoh::keformat!(ke_admin_prefix::formatter(), plugin_id = &self.plugin_id).unwrap(); let admin_keyexpr_expr = (&admin_prefix) / *KE_ANY_N_SEGMENT; - log::debug!("Declare admin space on {}", admin_keyexpr_expr); + tracing::debug!("Declare admin space on {}", admin_keyexpr_expr); let admin_queryable = self .zsession .declare_queryable(admin_keyexpr_expr) @@ -349,16 +349,16 @@ impl<'a> ROS2PluginRuntime<'a> { match evt { Ok(evt) => { if self.is_allowed(&evt) { - log::info!("{evt} - Allowed"); + tracing::info!("{evt} - Allowed"); // pass ROS2DiscoveryEvent to RoutesMgr if let Err(e) = routes_mgr.on_ros_discovery_event(evt).await { - log::warn!("Error updating route: {e}"); + tracing::warn!("Error updating route: {e}"); } } else { - log::debug!("{evt} - Denied per config"); + tracing::debug!("{evt} - Denied per config"); } } - Err(e) => log::error!("Internal Error: received from DiscoveryMgr: {e}") + Err(e) => tracing::error!("Internal Error: received from DiscoveryMgr: {e}") } }, @@ -376,31 +376,31 @@ impl<'a> ROS2PluginRuntime<'a> { match (parsed.remaining(), evt.kind) { // New remote bridge detected (None, SampleKind::Put) => { - log::info!("New ROS 2 bridge detected: {}", plugin_id); + tracing::info!("New ROS 2 bridge detected: {}", plugin_id); // make each routes for a TRANSIENT_LOCAL Subscriber to query historical publications from this new plugin routes_mgr.query_all_historical_publications(plugin_id).await; } // New remote bridge left - (None, SampleKind::Delete) => log::info!("Remote ROS 2 bridge left: {}", plugin_id), + (None, SampleKind::Delete) => tracing::info!("Remote ROS 2 bridge left: {}", plugin_id), // the liveliness token corresponds to a ROS2 announcement (Some(remaining), _) => { // parse it and pass ROS2AnnouncementEvent to RoutesMgr match self.parse_announcement_event(ke, &remaining.as_str()[..3], evt.kind) { Ok(evt) => { - log::info!("Remote bridge {plugin_id} {evt}"); + tracing::info!("Remote bridge {plugin_id} {evt}"); routes_mgr.on_ros_announcement_event(evt).await - .unwrap_or_else(|e| log::warn!("Error treating announcement event: {e}")); + .unwrap_or_else(|e| tracing::warn!("Error treating announcement event: {e}")); }, Err(e) => - log::warn!("Received unexpected liveliness key expression '{ke}': {e}") + tracing::warn!("Received unexpected liveliness key expression '{ke}': {e}") } } } } else { - log::warn!("Received unexpected liveliness key expression '{ke}'"); + tracing::warn!("Received unexpected liveliness key expression '{ke}'"); } }, - Err(e) => log::warn!("Error receiving liveliness event: {e}") + Err(e) => tracing::warn!("Error receiving liveliness event: {e}") } }, @@ -412,7 +412,7 @@ impl<'a> ROS2PluginRuntime<'a> { // pass query to discovery_mgr routes_mgr.treat_admin_query(&query).await; } else { - log::warn!("AdminSpace queryable was closed!"); + tracing::warn!("AdminSpace queryable was closed!"); } } ) @@ -426,7 +426,7 @@ impl<'a> ROS2PluginRuntime<'a> { sample_kind: SampleKind, ) -> Result { use ROS2AnnouncementEvent::*; - log::debug!("Received liveliness event: {sample_kind} on {liveliness_ke}"); + tracing::debug!("Received liveliness event: {sample_kind} on {liveliness_ke}"); match (iface_kind, sample_kind) { ("MP/", SampleKind::Put) => parse_ke_liveliness_pub(liveliness_ke) .map_err(|e| format!("Received invalid liveliness token: {e}")) @@ -579,7 +579,7 @@ impl<'a> ROS2PluginRuntime<'a> { AdminRef::Config => match serde_json::to_value(&*self.config) { Ok(v) => v.into(), Err(e) => { - log::error!("INTERNAL ERROR serializing config as JSON: {}", e); + tracing::error!("INTERNAL ERROR serializing config as JSON: {}", e); return; } }, @@ -589,7 +589,7 @@ impl<'a> ROS2PluginRuntime<'a> { .res_async() .await { - log::warn!("Error replying to admin query {:?}: {}", query, e); + tracing::warn!("Error replying to admin query {:?}: {}", query, e); } } } @@ -609,7 +609,7 @@ struct ChannelEvent { impl Timed for ChannelEvent { async fn run(&mut self) { if self.tx.send(()).is_err() { - log::warn!("Error sending periodic timer notification on channel"); + tracing::warn!("Error sending periodic timer notification on channel"); }; } } diff --git a/zenoh-plugin-ros2dds/src/node_info.rs b/zenoh-plugin-ros2dds/src/node_info.rs index 76e944b..c09e1a3 100644 --- a/zenoh-plugin-ros2dds/src/node_info.rs +++ b/zenoh-plugin-ros2dds/src/node_info.rs @@ -552,7 +552,7 @@ impl NodeInfo { &entity.key, ), _ => { - log::warn!( + tracing::warn!( r#"ROS Node {self} uses unexpected DDS topic "{}" - ignored"#, entity.topic_name ); @@ -626,7 +626,7 @@ impl NodeInfo { &entity.key, ), _ => { - log::warn!( + tracing::warn!( r#"ROS Node {self} uses unexpected DDS topic "{}" - ignored"#, entity.topic_name ); @@ -651,7 +651,7 @@ impl NodeInfo { Some(DiscoveredMsgPub(node_fullname, t)) } Err(e) => { - log::error!( + tracing::error!( "ROS Node {node_fullname} declared an incompatible Publisher: {e} - ignored" ); None @@ -661,7 +661,7 @@ impl NodeInfo { let v = e.get_mut(); let mut result: Option = None; if v.typ != typ { - log::error!( + tracing::error!( r#"ROS Node {node_fullname} declares 2 Publishers on same topic {name} but with different types: {} vs {typ} - Publisher with 2nd type ignored""#, v.typ ); @@ -690,7 +690,7 @@ impl NodeInfo { Some(DiscoveredMsgSub(node_fullname, t)) } Err(e) => { - log::error!( + tracing::error!( "ROS Node {node_fullname} declared an incompatible Subscriber: {e} - ignored" ); None @@ -700,7 +700,7 @@ impl NodeInfo { let v = e.get_mut(); let mut result: Option = None; if v.typ != typ { - log::error!( + tracing::error!( r#"ROS Node {node_fullname} declares 2 Subscriber on same topic {name} but with different types: {} vs {typ} - Publisher with 2nd type ignored""#, v.typ ); @@ -729,7 +729,7 @@ impl NodeInfo { s.entities.req_reader = *reader; e.insert(s); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Service Server: {e} - ignored" ), } @@ -739,7 +739,7 @@ impl NodeInfo { let v = e.get_mut(); let mut result = None; if v.typ != typ { - log::warn!( + tracing::warn!( r#"ROS declaration of Service Server "{v}" changed it's type to "{typ}""# ); v.typ = typ; @@ -749,7 +749,7 @@ impl NodeInfo { } if v.entities.req_reader != *reader { if v.entities.req_reader != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Service Server "{v}" changed it's Request DDS Reader's GID from {} to {reader}"#, v.entities.req_reader ); @@ -780,7 +780,7 @@ impl NodeInfo { s.entities.rep_writer = *writer; e.insert(s); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Service Server: {e} - ignored" ), } @@ -790,7 +790,7 @@ impl NodeInfo { let v = e.get_mut(); let mut result = None; if v.typ != typ { - log::warn!( + tracing::warn!( r#"ROS declaration of Service Server "{v}" changed it's type to "{typ}""# ); v.typ = typ; @@ -800,7 +800,7 @@ impl NodeInfo { } if v.entities.rep_writer != *writer { if v.entities.rep_writer != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Service Server "{v}" changed it's Reply DDS Writer's GID from {} to {writer}"#, v.entities.rep_writer ); @@ -831,7 +831,7 @@ impl NodeInfo { s.entities.rep_reader = *reader; e.insert(s); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Service Client: {e} - ignored" ), } @@ -841,7 +841,7 @@ impl NodeInfo { let v = e.get_mut(); let mut result = None; if v.typ != typ { - log::warn!( + tracing::warn!( r#"ROS declaration of Service Client "{v}" changed it's type to "{typ}""# ); v.typ = typ; @@ -851,7 +851,7 @@ impl NodeInfo { } if v.entities.rep_reader != *reader { if v.entities.rep_reader != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Service Client "{v}" changed it's Request DDS Reader's GID from {} to {reader}"#, v.entities.rep_reader ); @@ -882,7 +882,7 @@ impl NodeInfo { s.entities.req_writer = *writer; e.insert(s); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Service Client: {e} - ignored" ), } @@ -892,7 +892,7 @@ impl NodeInfo { let v = e.get_mut(); let mut result = None; if v.typ != typ { - log::warn!( + tracing::warn!( r#"ROS declaration of Service Server "{v}" changed it's type to "{typ}""# ); v.typ = typ; @@ -902,7 +902,7 @@ impl NodeInfo { } if v.entities.req_writer != *writer { if v.entities.req_writer != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Service Server "{v}" changed it's Reply DDS Writer's GID from {} to {writer}"#, v.entities.req_writer ); @@ -933,7 +933,7 @@ impl NodeInfo { a.entities.send_goal.req_reader = *reader; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Server: {e} - ignored" ), } @@ -944,7 +944,7 @@ impl NodeInfo { let mut result = None; if v.typ != typ { if !v.typ.is_empty() { - log::warn!( + tracing::warn!( r#"ROS declaration of Action Server "{v}" changed it's type to "{typ}""# ); } @@ -955,7 +955,7 @@ impl NodeInfo { } if v.entities.send_goal.req_reader != *reader { if v.entities.send_goal.req_reader != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Server "{v}" changed it's send_goal Request DDS Reader's GID from {} to {reader}"#, v.entities.send_goal.req_reader ); @@ -986,7 +986,7 @@ impl NodeInfo { a.entities.send_goal.rep_writer = *writer; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Server: {e} - ignored" ), } @@ -997,7 +997,7 @@ impl NodeInfo { let mut result = None; if v.typ != typ { if !v.typ.is_empty() { - log::warn!( + tracing::warn!( r#"ROS declaration of Action Server "{v}" changed it's type to "{typ}""# ); } @@ -1008,7 +1008,7 @@ impl NodeInfo { } if v.entities.send_goal.rep_writer != *writer { if v.entities.send_goal.rep_writer != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Server "{v}" changed it's send_goal Reply DDS Writer's GID from {} to {writer}"#, v.entities.send_goal.rep_writer ); @@ -1040,7 +1040,7 @@ impl NodeInfo { a.entities.cancel_goal.req_reader = *reader; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Server: {e} - ignored" ), } @@ -1051,7 +1051,7 @@ impl NodeInfo { let mut result = None; if v.entities.cancel_goal.req_reader != *reader { if v.entities.cancel_goal.req_reader != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Server "{v}" changed it's cancel_goal Request DDS Reader's GID from {} to {reader}"#, v.entities.cancel_goal.req_reader ); @@ -1083,7 +1083,7 @@ impl NodeInfo { a.entities.cancel_goal.rep_writer = *writer; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Server: {e} - ignored" ), } @@ -1094,7 +1094,7 @@ impl NodeInfo { let mut result = None; if v.entities.cancel_goal.rep_writer != *writer { if v.entities.cancel_goal.rep_writer != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Server "{v}" changed it's cancel_goal Reply DDS Writer's GID from {} to {writer}"#, v.entities.cancel_goal.rep_writer ); @@ -1125,7 +1125,7 @@ impl NodeInfo { a.entities.get_result.req_reader = *reader; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Server: {e} - ignored" ), } @@ -1136,7 +1136,7 @@ impl NodeInfo { let mut result = None; if v.typ != typ { if !v.typ.is_empty() { - log::warn!( + tracing::warn!( r#"ROS declaration of Action Server "{v}" changed it's type to "{typ}""# ); } @@ -1147,7 +1147,7 @@ impl NodeInfo { } if v.entities.get_result.req_reader != *reader { if v.entities.get_result.req_reader != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Server "{v}" changed it's get_result Request DDS Reader's GID from {} to {reader}"#, v.entities.get_result.req_reader ); @@ -1178,7 +1178,7 @@ impl NodeInfo { a.entities.get_result.rep_writer = *writer; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Server: {e} - ignored" ), } @@ -1189,7 +1189,7 @@ impl NodeInfo { let mut result = None; if v.typ != typ { if !v.typ.is_empty() { - log::warn!( + tracing::warn!( r#"ROS declaration of Action Server "{v}" changed it's type to "{typ}""# ); } @@ -1200,7 +1200,7 @@ impl NodeInfo { } if v.entities.get_result.rep_writer != *writer { if v.entities.get_result.rep_writer != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Server "{v}" changed it's get_result Reply DDS Writer's GID from {} to {writer}"#, v.entities.get_result.rep_writer ); @@ -1232,7 +1232,7 @@ impl NodeInfo { a.entities.status_writer = *writer; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Server: {e} - ignored" ), } @@ -1243,7 +1243,7 @@ impl NodeInfo { let mut result = None; if v.entities.status_writer != *writer { if v.entities.status_writer != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Server "{v}" changed it's status DDS Writer's GID from {} to {writer}"#, v.entities.status_writer ); @@ -1274,7 +1274,7 @@ impl NodeInfo { a.entities.feedback_writer = *writer; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Server: {e} - ignored" ), } @@ -1285,7 +1285,7 @@ impl NodeInfo { let mut result = None; if v.typ != typ { if !v.typ.is_empty() { - log::warn!( + tracing::warn!( r#"ROS declaration of Action Server "{v}" changed it's type to "{typ}""# ); } @@ -1296,7 +1296,7 @@ impl NodeInfo { } if v.entities.feedback_writer != *writer { if v.entities.feedback_writer != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Server "{v}" changed it's status DDS Writer's GID from {} to {writer}"#, v.entities.feedback_writer ); @@ -1327,7 +1327,7 @@ impl NodeInfo { a.entities.send_goal.rep_reader = *reader; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Client: {e} - ignored" ), } @@ -1338,7 +1338,7 @@ impl NodeInfo { let mut result = None; if v.typ != typ { if !v.typ.is_empty() { - log::warn!( + tracing::warn!( r#"ROS declaration of Action Client "{v}" changed it's type to "{typ}""# ); } @@ -1349,7 +1349,7 @@ impl NodeInfo { } if v.entities.send_goal.rep_reader != *reader { if v.entities.send_goal.rep_reader != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Client "{v}" changed it's send_goal Reply DDS Reader's GID from {} to {reader}"#, v.entities.send_goal.rep_reader ); @@ -1380,7 +1380,7 @@ impl NodeInfo { a.entities.send_goal.req_writer = *writer; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Client: {e} - ignored" ), } @@ -1391,7 +1391,7 @@ impl NodeInfo { let mut result = None; if v.typ != typ { if !v.typ.is_empty() { - log::warn!( + tracing::warn!( r#"ROS declaration of Action Client "{v}" changed it's type to "{typ}""# ); } @@ -1402,7 +1402,7 @@ impl NodeInfo { } if v.entities.send_goal.req_writer != *writer { if v.entities.send_goal.req_writer != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Client "{v}" changed it's send_goal Request DDS Writer's GID from {} to {writer}"#, v.entities.send_goal.req_writer ); @@ -1434,7 +1434,7 @@ impl NodeInfo { a.entities.cancel_goal.rep_reader = *reader; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Client: {e} - ignored" ), } @@ -1445,7 +1445,7 @@ impl NodeInfo { let mut result = None; if v.entities.cancel_goal.rep_reader != *reader { if v.entities.cancel_goal.rep_reader != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Client "{v}" changed it's cancel_goal Reply DDS Reader's GID from {} to {reader}"#, v.entities.cancel_goal.rep_reader ); @@ -1477,7 +1477,7 @@ impl NodeInfo { a.entities.cancel_goal.req_writer = *writer; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Client: {e} - ignored" ), } @@ -1488,7 +1488,7 @@ impl NodeInfo { let mut result = None; if v.entities.cancel_goal.req_writer != *writer { if v.entities.cancel_goal.req_writer != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Client "{v}" changed it's cancel_goal Request DDS Writer's GID from {} to {writer}"#, v.entities.cancel_goal.req_writer ); @@ -1519,7 +1519,7 @@ impl NodeInfo { a.entities.get_result.rep_reader = *reader; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Client: {e} - ignored" ), } @@ -1530,7 +1530,7 @@ impl NodeInfo { let mut result = None; if v.typ != typ { if !v.typ.is_empty() { - log::warn!( + tracing::warn!( r#"ROS declaration of Action Client "{v}" changed it's type to "{typ}""# ); } @@ -1541,7 +1541,7 @@ impl NodeInfo { } if v.entities.get_result.rep_reader != *reader { if v.entities.get_result.rep_reader != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Client "{v}" changed it's get_result Reply DDS Reader's GID from {} to {reader}"#, v.entities.get_result.rep_reader ); @@ -1572,7 +1572,7 @@ impl NodeInfo { a.entities.get_result.req_writer = *writer; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Client: {e} - ignored" ), } @@ -1583,7 +1583,7 @@ impl NodeInfo { let mut result = None; if v.typ != typ { if !v.typ.is_empty() { - log::warn!( + tracing::warn!( r#"ROS declaration of Action Client "{v}" changed it's type to "{typ}""# ); } @@ -1594,7 +1594,7 @@ impl NodeInfo { } if v.entities.get_result.req_writer != *writer { if v.entities.get_result.req_writer != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Client "{v}" changed it's get_result Request DDS Writer's GID from {} to {writer}"#, v.entities.get_result.req_writer ); @@ -1626,7 +1626,7 @@ impl NodeInfo { a.entities.status_reader = *reader; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Client: {e} - ignored" ), } @@ -1637,7 +1637,7 @@ impl NodeInfo { let mut result = None; if v.entities.status_reader != *reader { if v.entities.status_reader != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Client "{v}" changed it's status DDS Reader's GID from {} to {reader}"#, v.entities.status_reader ); @@ -1668,7 +1668,7 @@ impl NodeInfo { a.entities.feedback_reader = *reader; e.insert(a); } - Err(e) => log::error!( + Err(e) => tracing::error!( "ROS Node {self} declared an incompatible Action Client: {e} - ignored" ), } @@ -1679,7 +1679,7 @@ impl NodeInfo { let mut result = None; if v.typ != typ { if !v.typ.is_empty() { - log::warn!( + tracing::warn!( r#"ROS declaration of Action Client "{v}" changed it's type to "{typ}""# ); } @@ -1690,7 +1690,7 @@ impl NodeInfo { } if v.entities.feedback_reader != *reader { if v.entities.feedback_reader != Gid::NOT_DISCOVERED { - log::debug!( + tracing::debug!( r#"ROS declaration of Action Client "{v}" changed it's status DDS Reader's GID from {} to {reader}"#, v.entities.feedback_reader ); diff --git a/zenoh-plugin-ros2dds/src/ros2_utils.rs b/zenoh-plugin-ros2dds/src/ros2_utils.rs index a88ad10..d18c07c 100644 --- a/zenoh-plugin-ros2dds/src/ros2_utils.rs +++ b/zenoh-plugin-ros2dds/src/ros2_utils.rs @@ -53,11 +53,11 @@ lazy_static::lazy_static!( pub fn get_ros_distro() -> String { match std::env::var("ROS_DISTRO") { Ok(s) if !s.is_empty() => { - log::debug!("ROS_DISTRO detected: {s}"); + tracing::debug!("ROS_DISTRO detected: {s}"); s } Ok(_) | Err(VarError::NotPresent) => { - log::warn!( + tracing::warn!( "ROS_DISTRO environment variable is not set. \ Assuming '{ASSUMED_ROS_DISTRO}', but this could lead to errors on 'ros_discovery_info' \ (see https://github.com/eclipse-zenoh/zenoh-plugin-ros2dds/issues/21)" @@ -65,7 +65,7 @@ pub fn get_ros_distro() -> String { ASSUMED_ROS_DISTRO.to_string() } Err(VarError::NotUnicode(s)) => { - log::warn!( + tracing::warn!( "ROS_DISTRO environment variable is invalid ('{s:?}'). \ Assuming '{ASSUMED_ROS_DISTRO}', but this could lead to errors on 'ros_discovery_info' \ (see https://github.com/eclipse-zenoh/zenoh-plugin-ros2dds/issues/21)" diff --git a/zenoh-plugin-ros2dds/src/ros_discovery.rs b/zenoh-plugin-ros2dds/src/ros_discovery.rs index 91bf4a4..9b9a7bb 100644 --- a/zenoh-plugin-ros2dds/src/ros_discovery.rs +++ b/zenoh-plugin-ros2dds/src/ros_discovery.rs @@ -57,14 +57,14 @@ pub struct RosDiscoveryInfoMgr { impl Drop for RosDiscoveryInfoMgr { fn drop(&mut self) { if let Err(e) = delete_dds_entity(self.reader) { - log::warn!( + tracing::warn!( "Error dropping DDS reader on {}: {}", ROS_DISCOVERY_INFO_TOPIC_NAME, e ); } if let Err(e) = delete_dds_entity(self.writer) { - log::warn!( + tracing::warn!( "Error dropping DDS writer on {}: {}", ROS_DISCOVERY_INFO_TOPIC_NAME, e @@ -190,13 +190,13 @@ impl RosDiscoveryInfoMgr { _ = ros_disco_timer_rcv.recv_async() => { let (ref msg, ref mut has_changed) = *zwrite!(participant_entities_state); if *has_changed { - log::debug!("Publish update on 'ros_discovery_info' with {} writers and {} readers", + tracing::debug!("Publish update on 'ros_discovery_info' with {} writers and {} readers", msg.node_entities_info_seq.values().next().map_or(0, |n| n.writer_gid_seq.len()), msg.node_entities_info_seq.values().next().map_or(0, |n| n.reader_gid_seq.len()) ); - log::trace!("Publish update on 'ros_discovery_info': {msg:?}"); + tracing::trace!("Publish update on 'ros_discovery_info': {msg:?}"); Self::write(writer, msg).unwrap_or_else(|e| - log::error!("Failed to publish update on 'ros_discovery_info' topic: {e}") + tracing::error!("Failed to publish update on 'ros_discovery_info' topic: {e}") ); *has_changed = false; } @@ -277,7 +277,7 @@ impl RosDiscoveryInfoMgr { map.values() .filter_map(|sample| { - log::trace!("Deserialize ParticipantEntitiesInfo: {:?}", sample); + tracing::trace!("Deserialize ParticipantEntitiesInfo: {:?}", sample); match cdr::deserialize_from::<_, ParticipantEntitiesInfo, _>( ZBuf::from(sample).reader(), cdr::size::Infinite, @@ -291,7 +291,7 @@ impl RosDiscoveryInfoMgr { // This can be detected checking if list is empty but the size of the buffer is greater than // CDR_header + GID + seq_len = 4 + 16 + 8 = 28 if !ros_distro_is_less_than("iron") && i.node_entities_info_seq.is_empty() && sample.len() > 28 { - log::warn!("Received invalid message on `ros_discovery_info` topic: {sample:?} \ + tracing::warn!("Received invalid message on `ros_discovery_info` topic: {sample:?} \ This bridge is configured with 'ROS_DISTRO={}' and expects GIDs to be 16 bytes. \ Here it seems the message comes from a ROS nodes with version older than 'iron' and using 24 bytes GIDs. \ If yes, please set 'ROS_DISTRO' environment variable to the same version than your ROS nodes", *ROS_DISTRO); @@ -299,7 +299,7 @@ impl RosDiscoveryInfoMgr { Some(i) }, Err(e) => { - log::warn!( + tracing::warn!( "Error receiving ParticipantEntitiesInfo on ros_discovery_info: {} - payload: {}", e, sample.hex_encode() ); diff --git a/zenoh-plugin-ros2dds/src/route_action_cli.rs b/zenoh-plugin-ros2dds/src/route_action_cli.rs index 468956c..411ddae 100644 --- a/zenoh-plugin-ros2dds/src/route_action_cli.rs +++ b/zenoh-plugin-ros2dds/src/route_action_cli.rs @@ -164,7 +164,7 @@ impl RouteActionCli<'_> { &self.zenoh_key_expr_prefix, &self.ros2_type, )?; - log::debug!("{self} announce via token {liveliness_ke}"); + tracing::debug!("{self} announce via token {liveliness_ke}"); let ros2_name = self.ros2_name.clone(); self.liveliness_token = Some(self.context.zsession .liveliness() @@ -182,7 +182,7 @@ impl RouteActionCli<'_> { // Retire the route over Zenoh removing the LivelinessToken fn retire_route(&mut self) { - log::debug!("{self} retire"); + tracing::debug!("{self} retire"); // Drop Zenoh Publisher and Liveliness token // The DDS Writer remains to be discovered by local ROS nodes self.is_active = false; @@ -213,7 +213,7 @@ impl RouteActionCli<'_> { ); self.remote_routes .insert(format!("{plugin_id}:{zenoh_key_expr_prefix}")); - log::debug!("{self} now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self} now serving remote routes {:?}", self.remote_routes); } #[inline] @@ -240,7 +240,7 @@ impl RouteActionCli<'_> { ); self.remote_routes .remove(&format!("{plugin_id}:{zenoh_key_expr_prefix}")); - log::debug!("{self} now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self} now serving remote routes {:?}", self.remote_routes); } #[inline] @@ -256,11 +256,11 @@ impl RouteActionCli<'_> { ); self.local_nodes.insert(node); - log::debug!("{self} now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self} now serving local nodes {:?}", self.local_nodes); // if 1st local node added, activate the route if self.local_nodes.len() == 1 { if let Err(e) = self.announce_route().await { - log::error!("{self} activation failed: {e}"); + tracing::error!("{self} activation failed: {e}"); } } } @@ -274,7 +274,7 @@ impl RouteActionCli<'_> { self.route_status.remove_local_node(node); self.local_nodes.remove(node); - log::debug!("{self} now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self} now serving local nodes {:?}", self.local_nodes); // if last local node removed, deactivate the route if self.local_nodes.is_empty() { self.retire_route(); diff --git a/zenoh-plugin-ros2dds/src/route_action_srv.rs b/zenoh-plugin-ros2dds/src/route_action_srv.rs index 3905721..369f76e 100644 --- a/zenoh-plugin-ros2dds/src/route_action_srv.rs +++ b/zenoh-plugin-ros2dds/src/route_action_srv.rs @@ -150,7 +150,7 @@ impl RouteActionSrv<'_> { &self.zenoh_key_expr_prefix, &self.ros2_type, )?; - log::debug!("{self} announce via token {liveliness_ke}"); + tracing::debug!("{self} announce via token {liveliness_ke}"); let ros2_name = self.ros2_name.clone(); self.liveliness_token = Some(self.context.zsession .liveliness() @@ -168,7 +168,7 @@ impl RouteActionSrv<'_> { // Retire the route over Zenoh removing the LivelinessToken fn retire_route(&mut self) { - log::debug!("{self} retire"); + tracing::debug!("{self} retire"); // Drop Zenoh Publisher and Liveliness token // The DDS Writer remains to be discovered by local ROS nodes self.is_active = false; @@ -199,7 +199,7 @@ impl RouteActionSrv<'_> { ); self.remote_routes .insert(format!("{plugin_id}:{zenoh_key_expr_prefix}")); - log::debug!("{self} now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self} now serving remote routes {:?}", self.remote_routes); } #[inline] @@ -226,7 +226,7 @@ impl RouteActionSrv<'_> { ); self.remote_routes .remove(&format!("{plugin_id}:{zenoh_key_expr_prefix}")); - log::debug!("{self} now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self} now serving remote routes {:?}", self.remote_routes); } #[inline] @@ -242,11 +242,11 @@ impl RouteActionSrv<'_> { ); self.local_nodes.insert(node); - log::debug!("{self} now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self} now serving local nodes {:?}", self.local_nodes); // if 1st local node added, activate the route if self.local_nodes.len() == 1 { if let Err(e) = self.announce_route().await { - log::error!("{self} activation failed: {e}"); + tracing::error!("{self} activation failed: {e}"); } } } @@ -260,7 +260,7 @@ impl RouteActionSrv<'_> { self.route_status.remove_local_node(node); self.local_nodes.remove(node); - log::debug!("{self} now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self} now serving local nodes {:?}", self.local_nodes); // if last local node removed, deactivate the route if self.local_nodes.is_empty() { self.retire_route(); diff --git a/zenoh-plugin-ros2dds/src/route_publisher.rs b/zenoh-plugin-ros2dds/src/route_publisher.rs index b9c2f6f..6b65a7c 100644 --- a/zenoh-plugin-ros2dds/src/route_publisher.rs +++ b/zenoh-plugin-ros2dds/src/route_publisher.rs @@ -127,7 +127,7 @@ impl RoutePublisher<'_> { reader_qos: Qos, context: Context, ) -> Result, String> { - log::debug!( + tracing::debug!( "Route Publisher ({ros2_name} -> {zenoh_key_expr}): creation with type {ros2_type}" ); @@ -159,7 +159,7 @@ impl RoutePublisher<'_> { }; // In case there are several Writers served by this route, increase the cache size history = history.saturating_mul(context.config.transient_local_cache_multiplier); - log::debug!( + tracing::debug!( "Route Publisher ({ros2_name} -> {zenoh_key_expr}): caching TRANSIENT_LOCAL publications via a PublicationCache with history={history} (computed from Reader's QoS: history=({:?},{}), durability_service.max_instances={})", history_qos.kind, history_qos.depth, durability_service_qos.max_instances ); @@ -229,7 +229,7 @@ impl RoutePublisher<'_> { let publisher = publisher.clone(); move |status| { - log::debug!("{route_id} MatchingStatus changed: {status:?}"); + tracing::debug!("{route_id} MatchingStatus changed: {status:?}"); if status.matching_subscribers() { if let Err(e) = activate_dds_reader( &dds_reader, @@ -242,7 +242,7 @@ impl RoutePublisher<'_> { &type_info, &publisher, ) { - log::error!("{route_id}: failed to activate DDS Reader: {e}"); + tracing::error!("{route_id}: failed to activate DDS Reader: {e}"); } } else { deactivate_dds_reader( @@ -286,10 +286,10 @@ impl RoutePublisher<'_> { // remove reader's GID from ros_discovery_info message match get_guid(&dds_reader) { Ok(gid) => self.context.ros_discovery_mgr.remove_dds_reader(gid), - Err(e) => log::warn!("{self}: {e}"), + Err(e) => tracing::warn!("{self}: {e}"), } if let Err(e) = delete_dds_entity(dds_reader) { - log::warn!("{}: error deleting DDS Reader: {}", self, e); + tracing::warn!("{}: error deleting DDS Reader: {}", self, e); } } } @@ -329,14 +329,14 @@ impl RoutePublisher<'_> { pub fn add_remote_route(&mut self, plugin_id: &str, zenoh_key_expr: &keyexpr) { self.remote_routes .insert(format!("{plugin_id}:{zenoh_key_expr}")); - log::debug!("{self} now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self} now serving remote routes {:?}", self.remote_routes); } #[inline] pub fn remove_remote_route(&mut self, plugin_id: &str, zenoh_key_expr: &keyexpr) { self.remote_routes .remove(&format!("{plugin_id}:{zenoh_key_expr}")); - log::debug!("{self} now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self} now serving remote routes {:?}", self.remote_routes); // if last remote route removed, deactivate the DDS Reader if self.remote_routes.is_empty() { self.deactivate_dds_reader(); @@ -351,11 +351,11 @@ impl RoutePublisher<'_> { #[inline] pub async fn add_local_node(&mut self, node: String, discovered_writer_qos: &Qos) { if self.local_nodes.insert(node) { - log::debug!("{self} now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self} now serving local nodes {:?}", self.local_nodes); // if 1st local node added, announce the route if self.local_nodes.len() == 1 { if let Err(e) = self.announce_route(discovered_writer_qos).await { - log::error!("{self} announcement failed: {e}"); + tracing::error!("{self} announcement failed: {e}"); } } } @@ -364,7 +364,7 @@ impl RoutePublisher<'_> { #[inline] pub fn remove_local_node(&mut self, node: &str) { if self.local_nodes.remove(node) { - log::debug!("{self} now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self} now serving local nodes {:?}", self.local_nodes); // if last local node removed, retire the route if self.local_nodes.is_empty() { self.retire_route(); @@ -416,7 +416,7 @@ fn activate_dds_reader( type_info: &Option>, publisher: &Arc>, ) -> Result<(), String> { - log::debug!("{route_id}: create Reader with {reader_qos:?}"); + tracing::debug!("{route_id}: create Reader with {reader_qos:?}"); let topic_name: String = format!("rt{}", ros2_name); let type_name = ros2_message_type_to_dds_type(ros2_type); let read_period = get_read_period(&context.config, ros2_name); @@ -443,9 +443,9 @@ fn activate_dds_reader( context.ros_discovery_mgr.add_dds_reader(get_guid(&reader)?); if old != DDS_ENTITY_NULL { - log::warn!("{route_id}: on activation their was already a DDS Reader - overwrite it"); + tracing::warn!("{route_id}: on activation their was already a DDS Reader - overwrite it"); if let Err(e) = delete_dds_entity(old) { - log::warn!("{route_id}: failed to delete overwritten DDS Reader: {e}"); + tracing::warn!("{route_id}: failed to delete overwritten DDS Reader: {e}"); } } @@ -457,27 +457,27 @@ fn deactivate_dds_reader( route_id: &str, ros_discovery_mgr: &Arc, ) { - log::debug!("{route_id}: delete Reader"); + tracing::debug!("{route_id}: delete Reader"); let reader = dds_reader.swap(DDS_ENTITY_NULL, Ordering::Relaxed); if reader != DDS_ENTITY_NULL { // remove reader's GID from ros_discovery_info message match get_guid(&reader) { Ok(gid) => ros_discovery_mgr.remove_dds_reader(gid), - Err(e) => log::warn!("{route_id}: {e}"), + Err(e) => tracing::warn!("{route_id}: {e}"), } if let Err(e) = delete_dds_entity(reader) { - log::warn!("{route_id}: error deleting DDS Reader: {e}"); + tracing::warn!("{route_id}: error deleting DDS Reader: {e}"); } } } fn route_dds_message_to_zenoh(sample: &DDSRawSample, publisher: &Arc, route_id: &str) { if *LOG_PAYLOAD { - log::debug!("{route_id}: routing message - payload: {:02x?}", sample); + tracing::debug!("{route_id}: routing message - payload: {:02x?}", sample); } else { - log::trace!("{route_id}: routing message - {} bytes", sample.len()); + tracing::trace!("{route_id}: routing message - {} bytes", sample.len()); } if let Err(e) = publisher.put(sample).res_sync() { - log::error!("{route_id}: failed to route message: {e}"); + tracing::error!("{route_id}: failed to route message: {e}"); } } diff --git a/zenoh-plugin-ros2dds/src/route_service_cli.rs b/zenoh-plugin-ros2dds/src/route_service_cli.rs index d331e65..606a0f0 100644 --- a/zenoh-plugin-ros2dds/src/route_service_cli.rs +++ b/zenoh-plugin-ros2dds/src/route_service_cli.rs @@ -100,7 +100,7 @@ impl RouteServiceCli<'_> { queries_timeout: Duration, context: Context, ) -> Result, String> { - log::debug!( + tracing::debug!( "Route Service Client (ROS:{ros2_name} <-> Zenoh:{zenoh_key_expr}): creation with type {ros2_type}" ); Ok(RouteServiceCli { @@ -129,7 +129,7 @@ impl RouteServiceCli<'_> { &self.zenoh_key_expr, &self.ros2_type, )?; - log::debug!("{self}: announce via token {liveliness_ke}"); + tracing::debug!("{self}: announce via token {liveliness_ke}"); let ros2_name = self.ros2_name.clone(); self.liveliness_token = Some(self.context.zsession .liveliness() @@ -148,14 +148,14 @@ impl RouteServiceCli<'_> { // Retire the route over Zenoh removing the LivelinessToken fn retire_route(&mut self) { - log::debug!("{self}: retire"); + tracing::debug!("{self}: retire"); // Drop Zenoh Publisher and Liveliness token // The DDS Writer remains to be discovered by local ROS nodes self.liveliness_token = None; } fn activate(&mut self) -> Result<(), String> { - log::debug!("{self}: activate"); + tracing::debug!("{self}: activate"); // Default Service QoS let mut qos = QOS_DEFAULT_SERVICE.clone(); @@ -164,7 +164,7 @@ impl RouteServiceCli<'_> { let server_id_str = new_service_id(&self.context.participant)?; let user_data = format!("serviceid= {server_id_str};"); qos.user_data = Some(user_data.into_bytes()); - log::debug!( + tracing::debug!( "{self}: using id '{server_id_str}' => USER_DATA={:?}", qos.user_data.as_ref().unwrap() ); @@ -181,9 +181,9 @@ impl RouteServiceCli<'_> { )?; let old = self.rep_writer.swap(rep_writer, Ordering::Relaxed); if old != DDS_ENTITY_NULL { - log::warn!("{self}: on activation their was already a DDS Reply Writer - overwrite it"); + tracing::warn!("{self}: on activation their was already a DDS Reply Writer - overwrite it"); if let Err(e) = delete_dds_entity(old) { - log::warn!("{self}: failed to delete overwritten DDS Reply Writer: {e}"); + tracing::warn!("{self}: failed to delete overwritten DDS Reply Writer: {e}"); } } @@ -220,11 +220,11 @@ impl RouteServiceCli<'_> { )?; let old = self.req_reader.swap(req_reader, Ordering::Relaxed); if old != DDS_ENTITY_NULL { - log::warn!( + tracing::warn!( "{self}: on activation their was already a DDS Request Reader - overwrite it" ); if let Err(e) = delete_dds_entity(old) { - log::warn!("{self}: failed to delete overwritten DDS Request Reader: {e}"); + tracing::warn!("{self}: failed to delete overwritten DDS Request Reader: {e}"); } } @@ -238,16 +238,16 @@ impl RouteServiceCli<'_> { } fn deactivate(&mut self) { - log::debug!("{self}: Deactivate"); + tracing::debug!("{self}: Deactivate"); let req_reader = self.req_reader.swap(DDS_ENTITY_NULL, Ordering::Relaxed); if req_reader != DDS_ENTITY_NULL { // remove reader's GID from ros_discovery_info message match get_guid(&req_reader) { Ok(gid) => self.context.ros_discovery_mgr.remove_dds_reader(gid), - Err(e) => log::warn!("{self}: {e}"), + Err(e) => tracing::warn!("{self}: {e}"), } if let Err(e) = delete_dds_entity(req_reader) { - log::warn!("{}: error deleting DDS Reader: {}", self, e); + tracing::warn!("{}: error deleting DDS Reader: {}", self, e); } } let rep_writer = self.rep_writer.swap(DDS_ENTITY_NULL, Ordering::Relaxed); @@ -255,10 +255,10 @@ impl RouteServiceCli<'_> { // remove writer's GID from ros_discovery_info message match get_guid(&req_reader) { Ok(gid) => self.context.ros_discovery_mgr.remove_dds_writer(gid), - Err(e) => log::warn!("{self}: {e}"), + Err(e) => tracing::warn!("{self}: {e}"), } if let Err(e) = delete_dds_entity(rep_writer) { - log::warn!("{}: error deleting DDS Writer: {}", self, e); + tracing::warn!("{}: error deleting DDS Writer: {}", self, e); } } self.is_active = false; @@ -268,7 +268,7 @@ impl RouteServiceCli<'_> { pub fn add_remote_route(&mut self, plugin_id: &str, zenoh_key_expr: &keyexpr) { self.remote_routes .insert(format!("{plugin_id}:{zenoh_key_expr}")); - log::debug!("{self}: now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self}: now serving remote routes {:?}", self.remote_routes); // if 1st remote node added (i.e. a Server has been announced), activate the route // NOTE: The route shall not be active if a remote Service Server have not been detected. // Otherwise, the Client will send a request to this route that will get no reply @@ -277,7 +277,7 @@ impl RouteServiceCli<'_> { // when available in zenoh... if self.remote_routes.len() == 1 { if let Err(e) = self.activate() { - log::error!("{self}: activation failed: {e}"); + tracing::error!("{self}: activation failed: {e}"); } } } @@ -286,7 +286,7 @@ impl RouteServiceCli<'_> { pub fn remove_remote_route(&mut self, plugin_id: &str, zenoh_key_expr: &keyexpr) { self.remote_routes .remove(&format!("{plugin_id}:{zenoh_key_expr}")); - log::debug!("{self}: now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self}: now serving remote routes {:?}", self.remote_routes); // if last remote node removed, deactivate the route if self.remote_routes.is_empty() { self.deactivate(); @@ -301,11 +301,11 @@ impl RouteServiceCli<'_> { #[inline] pub async fn add_local_node(&mut self, node: String) { self.local_nodes.insert(node); - log::debug!("{self}: now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self}: now serving local nodes {:?}", self.local_nodes); // if 1st local node added, announce the route if self.local_nodes.len() == 1 { if let Err(e) = self.announce_route().await { - log::error!("{self}: announcement failed: {e}"); + tracing::error!("{self}: announcement failed: {e}"); } } } @@ -313,7 +313,7 @@ impl RouteServiceCli<'_> { #[inline] pub fn remove_local_node(&mut self, node: &str) { self.local_nodes.remove(node); - log::debug!("{self}: now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self}: now serving local nodes {:?}", self.local_nodes); // if last local node removed, retire the route if self.local_nodes.is_empty() { self.retire_route(); @@ -343,7 +343,7 @@ fn route_dds_request_to_zenoh( // the client guid (8 bytes) and a sequence_number (8 bytes). As per rmw_cyclonedds here: // https://github.com/ros2/rmw_cyclonedds/blob/2263814fab142ac19dd3395971fb1f358d22a653/rmw_cyclonedds_cpp/src/serdata.hpp#L73 if sample.len() < 20 { - log::warn!("{route_id}: received invalid request: {sample:0x?}"); + tracing::warn!("{route_id}: received invalid request: {sample:0x?}"); return; } @@ -367,9 +367,9 @@ fn route_dds_request_to_zenoh( zenoh_req_buf.push_zslice(slice.subslice(20, slice.len()).unwrap()); if *LOG_PAYLOAD { - log::debug!("{route_id}: routing request {request_id} from DDS to Zenoh - payload: {zenoh_req_buf:02x?}"); + tracing::debug!("{route_id}: routing request {request_id} from DDS to Zenoh - payload: {zenoh_req_buf:02x?}"); } else { - log::trace!( + tracing::trace!( "{route_id}: routing request {request_id} from DDS to Zenoh - {} bytes", zenoh_req_buf.len() ); @@ -391,7 +391,7 @@ fn route_dds_request_to_zenoh( if !reply_received1.swap(true, std::sync::atomic::Ordering::Relaxed) { route_zenoh_reply_to_dds(&route_id1, reply, request_id, rep_writer) } else { - log::warn!("{route_id1}: received more than 1 reply for request {request_id} - dropping the extra replies"); + tracing::warn!("{route_id1}: received more than 1 reply for request {request_id} - dropping the extra replies"); } }, drop: move || { @@ -399,14 +399,14 @@ fn route_dds_request_to_zenoh( // There is no way to send an error message as a reply to a ROS Service Client ! // (sending an invalid message will make it crash...) // We have no choice but to log the error and let the client hanging without reply, until a timeout (if set by the client) - log::warn!("{route_id2}: received NO reply for request {request_id} - cannot reply to client, it will hang until timeout"); + tracing::warn!("{route_id2}: received NO reply for request {request_id} - cannot reply to client, it will hang until timeout"); } }, } }) .res_sync() { - log::warn!("{route_id}: routing request {request_id} from DDS to Zenoh failed: {e}"); + tracing::warn!("{route_id}: routing request {request_id} from DDS to Zenoh failed: {e}"); } } @@ -450,7 +450,7 @@ fn route_zenoh_reply_to_dds( Ok(sample) => { let zenoh_rep_buf = sample.payload.contiguous(); if zenoh_rep_buf.len() < 4 || zenoh_rep_buf[1] > 1 { - log::warn!( + tracing::warn!( "{route_id}: received invalid reply from Zenoh for {request_id}: {zenoh_rep_buf:0x?}" ); return; @@ -465,22 +465,22 @@ fn route_zenoh_reply_to_dds( dds_rep_buf.extend_from_slice(&zenoh_rep_buf[4..]); if *LOG_PAYLOAD { - log::debug!("{route_id}: routing reply for {request_id} from Zenoh to DDS - payload: {dds_rep_buf:02x?}"); + tracing::debug!("{route_id}: routing reply for {request_id} from Zenoh to DDS - payload: {dds_rep_buf:02x?}"); } else { - log::trace!( + tracing::trace!( "{route_id}: routing reply for {request_id} from Zenoh to DDS - {} bytes", dds_rep_buf.len() ); } if let Err(e) = dds_write(rep_writer, dds_rep_buf) { - log::warn!( + tracing::warn!( "{route_id}: routing reply for {request_id} from Zenoh to DDS failed: {e}" ); } } Err(val) => { - log::warn!("{route_id}: received error as reply for {request_id}: {val}"); + tracing::warn!("{route_id}: received error as reply for {request_id}: {val}"); } } } diff --git a/zenoh-plugin-ros2dds/src/route_service_srv.rs b/zenoh-plugin-ros2dds/src/route_service_srv.rs index 8250a30..b17e3ca 100644 --- a/zenoh-plugin-ros2dds/src/route_service_srv.rs +++ b/zenoh-plugin-ros2dds/src/route_service_srv.rs @@ -85,19 +85,19 @@ impl Drop for RouteServiceSrv<'_> { // remove writer's GID from ros_discovery_info message match get_guid(&self.req_writer) { Ok(gid) => self.context.ros_discovery_mgr.remove_dds_writer(gid), - Err(e) => log::warn!("{self}: {e}"), + Err(e) => tracing::warn!("{self}: {e}"), } // remove reader's GID from ros_discovery_info message match get_guid(&self.rep_reader) { Ok(gid) => self.context.ros_discovery_mgr.remove_dds_reader(gid), - Err(e) => log::warn!("{self}: {e}"), + Err(e) => tracing::warn!("{self}: {e}"), } if let Err(e) = delete_dds_entity(self.req_writer) { - log::warn!("{}: error deleting DDS Writer: {}", self, e); + tracing::warn!("{}: error deleting DDS Writer: {}", self, e); } if let Err(e) = delete_dds_entity(self.rep_reader) { - log::warn!("{}: error deleting DDS Reader: {}", self, e); + tracing::warn!("{}: error deleting DDS Reader: {}", self, e); } } } @@ -122,7 +122,7 @@ impl RouteServiceSrv<'_> { context: Context, ) -> Result, String> { let route_id = format!("Route Service Server (ROS:{ros2_name} <-> Zenoh:{zenoh_key_expr})"); - log::debug!("{route_id}: creation with type {ros2_type}"); + tracing::debug!("{route_id}: creation with type {ros2_type}"); // Default Service QoS let mut qos = QOS_DEFAULT_SERVICE.clone(); @@ -152,7 +152,7 @@ impl RouteServiceSrv<'_> { // https://github.com/ros2/rmw_cyclonedds/blob/2263814fab142ac19dd3395971fb1f358d22a653/rmw_cyclonedds_cpp/src/rmw_node.cpp#L4848 let client_guid = get_instance_handle(req_writer)?; - log::debug!( + tracing::debug!( "{route_id}: (local client_guid={client_guid:02x?}) id='{client_id_str}' => USER_DATA={:?}", qos.user_data.as_ref().unwrap() ); @@ -263,7 +263,7 @@ impl RouteServiceSrv<'_> { &self.zenoh_key_expr, &self.ros2_type, )?; - log::debug!("{self} announce via token {liveliness_ke}"); + tracing::debug!("{self} announce via token {liveliness_ke}"); let ros2_name = self.ros2_name.clone(); self.liveliness_token = Some(self.context.zsession .liveliness() @@ -282,7 +282,7 @@ impl RouteServiceSrv<'_> { // Retire the route over Zenoh removing the LivelinessToken fn retire_route(&mut self) { - log::debug!("{self} retire"); + tracing::debug!("{self} retire"); // Drop Zenoh Publisher and Liveliness token // The DDS Writer remains to be discovered by local ROS nodes self.zenoh_queryable = None; @@ -293,14 +293,14 @@ impl RouteServiceSrv<'_> { pub fn add_remote_route(&mut self, plugin_id: &str, zenoh_key_expr: &keyexpr) { self.remote_routes .insert(format!("{plugin_id}:{zenoh_key_expr}")); - log::debug!("{self} now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self} now serving remote routes {:?}", self.remote_routes); } #[inline] pub fn remove_remote_route(&mut self, plugin_id: &str, zenoh_key_expr: &keyexpr) { self.remote_routes .remove(&format!("{plugin_id}:{zenoh_key_expr}")); - log::debug!("{self} now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self} now serving remote routes {:?}", self.remote_routes); } #[inline] @@ -311,11 +311,11 @@ impl RouteServiceSrv<'_> { #[inline] pub async fn add_local_node(&mut self, node: String) { self.local_nodes.insert(node); - log::debug!("{self} now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self} now serving local nodes {:?}", self.local_nodes); // if 1st local node added, activate the route if self.local_nodes.len() == 1 { if let Err(e) = self.announce_route().await { - log::error!("{self} activation failed: {e}"); + tracing::error!("{self} activation failed: {e}"); } } } @@ -323,7 +323,7 @@ impl RouteServiceSrv<'_> { #[inline] pub fn remove_local_node(&mut self, node: &str) { self.local_nodes.remove(node); - log::debug!("{self} now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self} now serving local nodes {:?}", self.local_nodes); // if last local node removed, deactivate the route if self.local_nodes.is_empty() { self.retire_route(); @@ -377,7 +377,7 @@ fn route_zenoh_request_to_dds( // The query comes with some payload. It's expected to be the Request type encoded as CDR (including 4 bytes header) let zenoh_req_buf = &*(value.payload.contiguous()); if zenoh_req_buf.len() < 4 || zenoh_req_buf[1] > 1 { - log::warn!("{route_id}: received invalid request: {zenoh_req_buf:0x?}"); + tracing::warn!("{route_id}: received invalid request: {zenoh_req_buf:0x?}"); return; } @@ -406,11 +406,11 @@ fn route_zenoh_request_to_dds( }; if *LOG_PAYLOAD { - log::debug!( + tracing::debug!( "{route_id}: routing request {request_id} from Zenoh to DDS - payload: {dds_req_buf:02x?}" ); } else { - log::trace!( + tracing::trace!( "{route_id}: routing request {request_id} from Zenoh to DDS - {} bytes", dds_req_buf.len() ); @@ -418,7 +418,7 @@ fn route_zenoh_request_to_dds( queries_in_progress.insert(request_id, query); if let Err(e) = dds_write(req_writer, dds_req_buf) { - log::warn!("{route_id}: routing request from Zenoh to DDS failed: {e}"); + tracing::warn!("{route_id}: routing request from Zenoh to DDS failed: {e}"); queries_in_progress.remove(&request_id); } } @@ -433,7 +433,7 @@ fn route_dds_reply_to_zenoh( // the request id as header (16 bytes). As per rmw_cyclonedds here: // https://github.com/ros2/rmw_cyclonedds/blob/2263814fab142ac19dd3395971fb1f358d22a653/rmw_cyclonedds_cpp/src/serdata.hpp#L73 if sample.len() < 20 { - log::warn!("{route_id}: received invalid response from DDS: {sample:0x?}"); + tracing::warn!("{route_id}: received invalid response from DDS: {sample:0x?}"); return; } @@ -459,9 +459,9 @@ fn route_dds_reply_to_zenoh( zenoh_rep_buf.push_zslice(slice.subslice(20, slice.len()).unwrap()); if *LOG_PAYLOAD { - log::debug!("{route_id}: routing reply {request_id} from DDS to Zenoh - payload: {zenoh_rep_buf:02x?}"); + tracing::debug!("{route_id}: routing reply {request_id} from DDS to Zenoh - payload: {zenoh_rep_buf:02x?}"); } else { - log::trace!( + tracing::trace!( "{route_id}: routing reply {request_id} from DDS to Zenoh - {} bytes", zenoh_rep_buf.len() ); @@ -471,10 +471,10 @@ fn route_dds_reply_to_zenoh( .reply(Ok(Sample::new(zenoh_key_expr, zenoh_rep_buf))) .res_sync() { - log::warn!("{route_id}: routing reply for request {request_id} from DDS to Zenoh failed: {e}"); + tracing::warn!("{route_id}: routing reply for request {request_id} from DDS to Zenoh failed: {e}"); } } - None => log::trace!( + None => tracing::trace!( "{route_id}: received response from DDS an unknown query: {request_id} - ignore it" ), } diff --git a/zenoh-plugin-ros2dds/src/route_subscriber.rs b/zenoh-plugin-ros2dds/src/route_subscriber.rs index 141c7e8..fb5509e 100644 --- a/zenoh-plugin-ros2dds/src/route_subscriber.rs +++ b/zenoh-plugin-ros2dds/src/route_subscriber.rs @@ -81,12 +81,12 @@ impl Drop for RouteSubscriber<'_> { // remove writer's GID from ros_discovery_info message match get_guid(&self.dds_writer) { Ok(gid) => self.context.ros_discovery_mgr.remove_dds_writer(gid), - Err(e) => log::warn!("{self}: {e}"), + Err(e) => tracing::warn!("{self}: {e}"), } - log::debug!("{self}: delete Writer"); + tracing::debug!("{self}: delete Writer"); if let Err(e) = delete_dds_entity(self.dds_writer) { - log::warn!("{}: error deleting DDS Reader: {}", self, e); + tracing::warn!("{}: error deleting DDS Reader: {}", self, e); } } } @@ -112,7 +112,7 @@ impl RouteSubscriber<'_> { context: Context, ) -> Result, String> { let transient_local = is_transient_local(&writer_qos); - log::debug!("Route Subscriber ({zenoh_key_expr} -> {ros2_name}): creation with type {ros2_type} (transient_local:{transient_local})"); + tracing::debug!("Route Subscriber ({zenoh_key_expr} -> {ros2_name}): creation with type {ros2_type} (transient_local:{transient_local})"); let topic_name = format!("rt{ros2_name}"); let type_name = ros2_message_type_to_dds_type(&ros2_type); @@ -129,7 +129,7 @@ impl RouteSubscriber<'_> { writer_qos.reliability = None; } - log::debug!( + tracing::debug!( "Route Subscriber ({zenoh_key_expr} -> {ros2_name}): create Writer with {writer_qos:?}" ); let dds_writer = create_dds_writer( @@ -162,7 +162,7 @@ impl RouteSubscriber<'_> { // Announce the route over Zenoh via a LivelinessToken async fn announce_route(&mut self, discovered_reader_qos: &Qos) -> Result<(), String> { - log::debug!("{self} activate"); + tracing::debug!("{self} activate"); // Callback routing message received by Zenoh subscriber to DDS Writer (if set) let ros2_name = self.ros2_name.clone(); let dds_writer = self.dds_writer; @@ -176,7 +176,7 @@ impl RouteSubscriber<'_> { // query all PublicationCaches on "/*/" let query_selector: Selector = (*KE_PREFIX_PUB_CACHE / *KE_ANY_1_SEGMENT / &self.zenoh_key_expr).into(); - log::debug!("{self}: query historical messages from everybody for TRANSIENT_LOCAL Reader on {query_selector}"); + tracing::debug!("{self}: query historical messages from everybody for TRANSIENT_LOCAL Reader on {query_selector}"); let sub = self .context .zsession @@ -235,7 +235,7 @@ impl RouteSubscriber<'_> { // Retire the route over Zenoh removing the LivelinessToken fn retire_route(&mut self) { - log::debug!("{self} deactivate"); + tracing::debug!("{self} deactivate"); // Drop Zenoh Subscriber and Liveliness token // The DDS Writer remains to be discovered by local ROS nodes self.zenoh_subscriber = None; @@ -249,7 +249,7 @@ impl RouteSubscriber<'_> { // query all PublicationCaches on "//" let query_selector: Selector = (*KE_PREFIX_PUB_CACHE / plugin_id / &self.zenoh_key_expr).into(); - log::debug!("Route Subscriber (Zenoh:{} -> ROS:{}): query historical messages from {plugin_id} for TRANSIENT_LOCAL Reader on {query_selector}", + tracing::debug!("Route Subscriber (Zenoh:{} -> ROS:{}): query historical messages from {plugin_id} for TRANSIENT_LOCAL Reader on {query_selector}", self.zenoh_key_expr, self.ros2_name ); @@ -273,7 +273,7 @@ impl RouteSubscriber<'_> { .res() .await { - log::warn!( + tracing::warn!( "{}: query for historical publications on {} failed: {}", self, query_selector, @@ -287,14 +287,14 @@ impl RouteSubscriber<'_> { pub fn add_remote_route(&mut self, plugin_id: &str, zenoh_key_expr: &keyexpr) { self.remote_routes .insert(format!("{plugin_id}:{zenoh_key_expr}")); - log::debug!("{self} now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self} now serving remote routes {:?}", self.remote_routes); } #[inline] pub fn remove_remote_route(&mut self, plugin_id: &str, zenoh_key_expr: &keyexpr) { self.remote_routes .remove(&format!("{plugin_id}:{zenoh_key_expr}")); - log::debug!("{self} now serving remote routes {:?}", self.remote_routes); + tracing::debug!("{self} now serving remote routes {:?}", self.remote_routes); } #[inline] @@ -305,11 +305,11 @@ impl RouteSubscriber<'_> { #[inline] pub async fn add_local_node(&mut self, entity_key: String, discovered_reader_qos: &Qos) { self.local_nodes.insert(entity_key); - log::debug!("{self} now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self} now serving local nodes {:?}", self.local_nodes); // if 1st local node added, activate the route if self.local_nodes.len() == 1 { if let Err(e) = self.announce_route(discovered_reader_qos).await { - log::error!("{self} activation failed: {e}"); + tracing::error!("{self} activation failed: {e}"); } } } @@ -317,7 +317,7 @@ impl RouteSubscriber<'_> { #[inline] pub fn remove_local_node(&mut self, entity_key: &str) { self.local_nodes.remove(entity_key); - log::debug!("{self} now serving local nodes {:?}", self.local_nodes); + tracing::debug!("{self} now serving local nodes {:?}", self.local_nodes); // if last local node removed, deactivate the route if self.local_nodes.is_empty() { self.retire_route(); @@ -337,14 +337,14 @@ impl RouteSubscriber<'_> { fn route_zenoh_message_to_dds(s: Sample, ros2_name: &str, data_writer: dds_entity_t) { if *LOG_PAYLOAD { - log::debug!( + tracing::debug!( "Route Subscriber (Zenoh:{} -> ROS:{}): routing message - payload: {:02x?}", s.key_expr, &ros2_name, s.value.payload ); } else { - log::trace!( + tracing::trace!( "Route Subscriber (Zenoh:{} -> ROS:{}): routing message - {} bytes", s.key_expr, &ros2_name, @@ -364,7 +364,7 @@ fn route_zenoh_message_to_dds(s: Sample, ros2_name: &str, data_writer: dds_entit let size: ddsrt_iov_len_t = match ddsrt_iov_len_from_usize(len) { Ok(s) => s, Err(_) => { - log::warn!( + tracing::warn!( "Route Subscriber (Zenoh:{} -> ROS:{}): can't route message; excessive payload size ({})", s.key_expr, ros2_name, @@ -382,7 +382,7 @@ fn route_zenoh_message_to_dds(s: Sample, ros2_name: &str, data_writer: dds_entit let mut sertype_ptr: *const ddsi_sertype = std::ptr::null_mut(); let ret = dds_get_entity_sertype(data_writer, &mut sertype_ptr); if ret < 0 { - log::warn!( + tracing::warn!( "Route Subscriber (Zenoh:{} -> ROS:{}): can't route message; sertype lookup failed ({})", s.key_expr, ros2_name, @@ -403,7 +403,7 @@ fn route_zenoh_message_to_dds(s: Sample, ros2_name: &str, data_writer: dds_entit let ret = dds_writecdr(data_writer, fwdp); if ret < 0 { - log::warn!( + tracing::warn!( "Route Subscriber (Zenoh:{} -> ROS:{}): DDS write({data_writer}) failed: {}", s.key_expr, ros2_name, diff --git a/zenoh-plugin-ros2dds/src/routes_mgr.rs b/zenoh-plugin-ros2dds/src/routes_mgr.rs index 657fe0f..16ed4cb 100644 --- a/zenoh-plugin-ros2dds/src/routes_mgr.rs +++ b/zenoh-plugin-ros2dds/src/routes_mgr.rs @@ -179,7 +179,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_PUBLISHER / iface.name_as_keyexpr())); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -227,7 +227,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_SUBSCRIBER / iface.name_as_keyexpr())); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -248,7 +248,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_SERVICE_SRV / iface.name_as_keyexpr())); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -269,7 +269,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_SERVICE_CLI / iface.name_as_keyexpr())); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -289,7 +289,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_ACTION_SRV / iface.name_as_keyexpr())); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -309,7 +309,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_ACTION_CLI / iface.name_as_keyexpr())); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -361,7 +361,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_SUBSCRIBER / &zenoh_key_expr)); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -404,7 +404,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_PUBLISHER / &zenoh_key_expr)); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -439,7 +439,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_SERVICE_CLI / &zenoh_key_expr)); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -474,7 +474,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_SERVICE_SRV / &zenoh_key_expr)); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -508,7 +508,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_SERVICE_CLI / &zenoh_key_expr)); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -542,7 +542,7 @@ impl<'a> RoutesMgr<'a> { self.admin_space .remove(&(*KE_PREFIX_ROUTE_SERVICE_SRV / &zenoh_key_expr)); let route = entry.remove(); - log::info!("{route} removed"); + tracing::info!("{route} removed"); } } } @@ -579,7 +579,7 @@ impl<'a> RoutesMgr<'a> { self.context.clone(), ) .await?; - log::info!("{route} created"); + tracing::info!("{route} created"); if admin_space_ref { // insert reference in admin_space @@ -616,7 +616,7 @@ impl<'a> RoutesMgr<'a> { self.context.clone(), ) .await?; - log::info!("{route} created"); + tracing::info!("{route} created"); if admin_space_ref { // insert reference in admin_space @@ -650,7 +650,7 @@ impl<'a> RoutesMgr<'a> { self.context.clone(), ) .await?; - log::info!("{route} created"); + tracing::info!("{route} created"); if admin_space_ref { // insert reference in admin_space @@ -687,7 +687,7 @@ impl<'a> RoutesMgr<'a> { self.context.clone(), ) .await?; - log::info!("{route} created"); + tracing::info!("{route} created"); if admin_space_ref { // insert reference in admin_space @@ -719,7 +719,7 @@ impl<'a> RoutesMgr<'a> { self.context.clone(), ) .await?; - log::info!("{route} created"); + tracing::info!("{route} created"); // insert reference in admin_space let admin_ke = *KE_PREFIX_ROUTE_ACTION_SRV / &zenoh_key_expr; @@ -749,7 +749,7 @@ impl<'a> RoutesMgr<'a> { self.context.clone(), ) .await?; - log::info!("{route} created"); + tracing::info!("{route} created"); // insert reference in admin_space let admin_ke = *KE_PREFIX_ROUTE_ACTION_CLI / &zenoh_key_expr; @@ -769,7 +769,7 @@ impl<'a> RoutesMgr<'a> { // the selector, if those keys had the admin_keyexpr_prefix. let sub_kes = selector.key_expr.strip_prefix(&self.admin_prefix); if sub_kes.is_empty() { - log::error!("Received query for admin space: '{}' - but it's not prefixed by admin_keyexpr_prefix='{}'", selector, &self.admin_prefix); + tracing::error!("Received query for admin space: '{}' - but it's not prefixed by admin_keyexpr_prefix='{}'", selector, &self.admin_prefix); return; } @@ -800,12 +800,12 @@ impl<'a> RoutesMgr<'a> { .res_async() .await { - log::warn!("Error replying to admin query {:?}: {}", query, e); + tracing::warn!("Error replying to admin query {:?}: {}", query, e); } } - Ok(None) => log::error!("INTERNAL ERROR: Dangling {:?} for {}", route_ref, key_expr), + Ok(None) => tracing::error!("INTERNAL ERROR: Dangling {:?} for {}", route_ref, key_expr), Err(e) => { - log::error!("INTERNAL ERROR serializing admin value as JSON: {}", e) + tracing::error!("INTERNAL ERROR serializing admin value as JSON: {}", e) } } } From 0494e96f6768228fa7ceb00b494edacec039d959 Mon Sep 17 00:00:00 2001 From: gabrik Date: Wed, 3 Apr 2024 14:36:08 +0200 Subject: [PATCH 2/3] chore: format Signed-off-by: gabrik --- zenoh-plugin-ros2dds/src/discovered_entities.rs | 4 +++- zenoh-plugin-ros2dds/src/route_service_cli.rs | 4 +++- zenoh-plugin-ros2dds/src/routes_mgr.rs | 4 +++- 3 files changed, 9 insertions(+), 3 deletions(-) diff --git a/zenoh-plugin-ros2dds/src/discovered_entities.rs b/zenoh-plugin-ros2dds/src/discovered_entities.rs index 9b6c377..bf4ce7b 100644 --- a/zenoh-plugin-ros2dds/src/discovered_entities.rs +++ b/zenoh-plugin-ros2dds/src/discovered_entities.rs @@ -456,7 +456,9 @@ impl DiscoveredEntities { tracing::warn!("Error replying to admin query {:?}: {}", query, e); } } - Ok(None) => tracing::error!("INTERNAL ERROR: Dangling {:?} for {}", entity_ref, key_expr), + Ok(None) => { + tracing::error!("INTERNAL ERROR: Dangling {:?} for {}", entity_ref, key_expr) + } Err(e) => { tracing::error!("INTERNAL ERROR serializing admin value as JSON: {}", e) } diff --git a/zenoh-plugin-ros2dds/src/route_service_cli.rs b/zenoh-plugin-ros2dds/src/route_service_cli.rs index 606a0f0..42821d4 100644 --- a/zenoh-plugin-ros2dds/src/route_service_cli.rs +++ b/zenoh-plugin-ros2dds/src/route_service_cli.rs @@ -181,7 +181,9 @@ impl RouteServiceCli<'_> { )?; let old = self.rep_writer.swap(rep_writer, Ordering::Relaxed); if old != DDS_ENTITY_NULL { - tracing::warn!("{self}: on activation their was already a DDS Reply Writer - overwrite it"); + tracing::warn!( + "{self}: on activation their was already a DDS Reply Writer - overwrite it" + ); if let Err(e) = delete_dds_entity(old) { tracing::warn!("{self}: failed to delete overwritten DDS Reply Writer: {e}"); } diff --git a/zenoh-plugin-ros2dds/src/routes_mgr.rs b/zenoh-plugin-ros2dds/src/routes_mgr.rs index 16ed4cb..0d4454d 100644 --- a/zenoh-plugin-ros2dds/src/routes_mgr.rs +++ b/zenoh-plugin-ros2dds/src/routes_mgr.rs @@ -803,7 +803,9 @@ impl<'a> RoutesMgr<'a> { tracing::warn!("Error replying to admin query {:?}: {}", query, e); } } - Ok(None) => tracing::error!("INTERNAL ERROR: Dangling {:?} for {}", route_ref, key_expr), + Ok(None) => { + tracing::error!("INTERNAL ERROR: Dangling {:?} for {}", route_ref, key_expr) + } Err(e) => { tracing::error!("INTERNAL ERROR serializing admin value as JSON: {}", e) } From ea2f1cf63ffa2b3a3efef1d7a6afcd01f39e15bd Mon Sep 17 00:00:00 2001 From: gabrik Date: Fri, 12 Apr 2024 08:05:43 +0200 Subject: [PATCH 3/3] feat(tracing): using zenoh main branch Signed-off-by: gabrik --- Cargo.lock | 123 ++++++++++++++----------------- Cargo.toml | 14 ++-- zenoh-bridge-ros2dds/src/main.rs | 2 +- zenoh-plugin-ros2dds/src/lib.rs | 4 +- 4 files changed, 66 insertions(+), 77 deletions(-) diff --git a/Cargo.lock b/Cargo.lock index 8ee714c..78b1a79 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -405,7 +405,7 @@ checksum = "bc00ceb34980c03614e35a3a4e218276a0a824e911d07651cd0d858a51e8c0f0" dependencies = [ "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] @@ -493,7 +493,7 @@ dependencies = [ "regex", "rustc-hash", "shlex", - "syn 2.0.55", + "syn 2.0.58", "which", ] @@ -718,7 +718,7 @@ dependencies = [ "heck", "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] @@ -1012,23 +1012,12 @@ dependencies = [ [[package]] name = "errno" -version = "0.3.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "136526188508e25c6fef639d7927dfb3e0e3084488bf202267829cf7fc23dbdd" -dependencies = [ - "errno-dragonfly", - "libc", - "windows-sys 0.48.0", -] - -[[package]] -name = "errno-dragonfly" -version = "0.1.2" +version = "0.3.8" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "aa68f1b12764fab894d2755d2518754e71b4fd80ecfb822714a1206c2aab39bf" +checksum = "a258e46cdc063eb8519c00b9fc845fc47bcfca4130e2f08e88665ceda8474245" dependencies = [ - "cc", "libc", + "windows-sys 0.52.0", ] [[package]] @@ -1197,7 +1186,7 @@ checksum = "89ca545a94061b6365f2c7355b4b32bd20df3ff95f02da9329b34ccc3bd6ee72" dependencies = [ "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] @@ -1684,9 +1673,9 @@ checksum = "ef53942eb7bf7ff43a617b3e2c1c4a5ecf5944a7c1bc12d7ee39bbb15e5c1519" [[package]] name = "linux-raw-sys" -version = "0.4.7" +version = "0.4.13" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1a9bad9f94746442c783ca431b22403b519cd7fbeed0533fdd6328b2f2212128" +checksum = "01cda141df6706de531b6c46c3a33ecca755538219bd484262fa09410c13539c" [[package]] name = "lock_api" @@ -2049,7 +2038,7 @@ dependencies = [ "pest_meta", "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] @@ -2090,7 +2079,7 @@ checksum = "4359fd9c9171ec6e8c62926d6faaf553a8dc3f64e1507e76da7911b4f6a04405" dependencies = [ "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] @@ -2204,7 +2193,7 @@ source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "8d3928fb5db768cb86f891ff014f0144589297e3c6a1aba6ed7cecfdace270c7" dependencies = [ "proc-macro2", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] @@ -2272,9 +2261,9 @@ dependencies = [ [[package]] name = "quote" -version = "1.0.35" +version = "1.0.36" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "291ec9ab5efd934aaf503a6466c5d5251535d108ee747472c3977cc5acc868ef" +checksum = "0fa76aaf39101c457836aec0ce2316dbdc3ab723cdda1c6bd4e6ad4208acaca7" dependencies = [ "proc-macro2", ] @@ -2536,15 +2525,15 @@ dependencies = [ [[package]] name = "rustix" -version = "0.38.13" +version = "0.38.32" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d7db8590df6dfcd144d22afd1b83b36c21a18d7cbc1dc4bb5295a8712e9eb662" +checksum = "65e04861e65f21776e67888bfbea442b3642beaa0138fdb1dd7a84a52dffdb89" dependencies = [ "bitflags 2.4.0", "errno", "libc", - "linux-raw-sys 0.4.7", - "windows-sys 0.48.0", + "linux-raw-sys 0.4.13", + "windows-sys 0.52.0", ] [[package]] @@ -2770,7 +2759,7 @@ checksum = "4eca7ac642d82aa35b60049a6eccb4be6be75e599bd2e9adb5f875a737654af2" dependencies = [ "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] @@ -3191,9 +3180,9 @@ dependencies = [ [[package]] name = "syn" -version = "2.0.55" +version = "2.0.58" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "002a1b3dbf967edfafc32655d0f377ab0bb7b994aa1d32c8cc7e9b8bf3ebb8f0" +checksum = "44cfb93f38070beee36b3fef7d4f5a16f27751d94b187b666a5cc5e9b0d30687" dependencies = [ "proc-macro2", "quote", @@ -3217,7 +3206,7 @@ checksum = "49922ecae66cc8a249b77e68d1d0623c1b2c514f0060c27cdc68bd62a1219d35" dependencies = [ "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] @@ -3367,7 +3356,7 @@ checksum = "5b8a1e28f2deaa14e508979454cb3a223b10b938b45af148bc0986de36f1923b" dependencies = [ "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] @@ -3439,7 +3428,7 @@ checksum = "5f4f31f56159e98206da9efd823404b79b6ef3143b4a7ab76e67b1751b25a4ab" dependencies = [ "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] @@ -3767,7 +3756,7 @@ dependencies = [ "once_cell", "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", "wasm-bindgen-shared", ] @@ -3801,7 +3790,7 @@ checksum = "54681b18a46765f095758388f2d0cf16eb8d4169b639ab575a8f5693af210c7b" dependencies = [ "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", "wasm-bindgen-backend", "wasm-bindgen-shared", ] @@ -3840,7 +3829,7 @@ dependencies = [ "either", "home", "once_cell", - "rustix 0.38.13", + "rustix 0.38.32", ] [[package]] @@ -4009,7 +3998,7 @@ checksum = "dff9641d1cd4be8d1a070daf9e3773c5f67e78b4d9d42263020c057706765c04" [[package]] name = "zenoh" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-trait", "base64 0.21.4", @@ -4076,7 +4065,7 @@ dependencies = [ [[package]] name = "zenoh-buffers" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "zenoh-collections", ] @@ -4084,7 +4073,7 @@ dependencies = [ [[package]] name = "zenoh-codec" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "serde", "tracing", @@ -4096,12 +4085,12 @@ dependencies = [ [[package]] name = "zenoh-collections" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" [[package]] name = "zenoh-config" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "flume", "json5", @@ -4121,7 +4110,7 @@ dependencies = [ [[package]] name = "zenoh-core" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-global-executor", "lazy_static", @@ -4133,7 +4122,7 @@ dependencies = [ [[package]] name = "zenoh-crypto" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "aes 0.8.3", "hmac 0.12.1", @@ -4146,7 +4135,7 @@ dependencies = [ [[package]] name = "zenoh-ext" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "bincode", "flume", @@ -4167,7 +4156,7 @@ dependencies = [ [[package]] name = "zenoh-keyexpr" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "hashbrown 0.14.0", "keyed-set", @@ -4181,7 +4170,7 @@ dependencies = [ [[package]] name = "zenoh-link" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-trait", "zenoh-config", @@ -4199,7 +4188,7 @@ dependencies = [ [[package]] name = "zenoh-link-commons" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-trait", "flume", @@ -4222,7 +4211,7 @@ dependencies = [ [[package]] name = "zenoh-link-quic" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-trait", "base64 0.21.4", @@ -4250,7 +4239,7 @@ dependencies = [ [[package]] name = "zenoh-link-tcp" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-trait", "tokio", @@ -4268,7 +4257,7 @@ dependencies = [ [[package]] name = "zenoh-link-tls" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-trait", "base64 0.21.4", @@ -4296,7 +4285,7 @@ dependencies = [ [[package]] name = "zenoh-link-udp" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-trait", "socket2 0.5.6", @@ -4317,7 +4306,7 @@ dependencies = [ [[package]] name = "zenoh-link-unixsock_stream" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-trait", "futures", @@ -4337,7 +4326,7 @@ dependencies = [ [[package]] name = "zenoh-link-ws" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-trait", "futures-util", @@ -4358,18 +4347,18 @@ dependencies = [ [[package]] name = "zenoh-macros" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", "zenoh-keyexpr", ] [[package]] name = "zenoh-plugin-rest" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "anyhow", "async-std", @@ -4424,7 +4413,7 @@ dependencies = [ [[package]] name = "zenoh-plugin-trait" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "const_format", "libloading", @@ -4440,7 +4429,7 @@ dependencies = [ [[package]] name = "zenoh-protocol" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "const_format", "rand 0.8.5", @@ -4454,7 +4443,7 @@ dependencies = [ [[package]] name = "zenoh-result" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "anyhow", ] @@ -4462,7 +4451,7 @@ dependencies = [ [[package]] name = "zenoh-runtime" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "futures", "lazy_static", @@ -4474,7 +4463,7 @@ dependencies = [ [[package]] name = "zenoh-sync" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "event-listener 4.0.0", "futures", @@ -4488,7 +4477,7 @@ dependencies = [ [[package]] name = "zenoh-task" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "futures", "tokio", @@ -4501,7 +4490,7 @@ dependencies = [ [[package]] name = "zenoh-transport" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-trait", "flume", @@ -4533,7 +4522,7 @@ dependencies = [ [[package]] name = "zenoh-util" version = "0.11.0-dev" -source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=feat/tracing#050290c15ff42cc76af446b17f158500a09b37bb" +source = "git+https://github.com/eclipse-zenoh/zenoh.git?branch=main#580f0b6142338c73d17da28b17986b0094272c6e" dependencies = [ "async-std", "async-trait", @@ -4570,7 +4559,7 @@ checksum = "9ce1b18ccd8e73a9321186f97e46f9f04b778851177567b1975109d26a08d2a6" dependencies = [ "proc-macro2", "quote", - "syn 2.0.55", + "syn 2.0.58", ] [[package]] diff --git a/Cargo.toml b/Cargo.toml index 8da3eed..c002d73 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -42,17 +42,17 @@ rustc_version = "0.4" serde = "1.0.154" serde_json = "1.0.94" tracing = "0.1" -zenoh = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing", features = [ +zenoh = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", features = [ "unstable", ] } -zenoh-collections = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing" } -zenoh-core = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing" } -zenoh-ext = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing", features = [ +zenoh-collections = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main" } +zenoh-core = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main" } +zenoh-ext = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", features = [ "unstable", ] } -zenoh-plugin-rest = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing", default-features = false } -zenoh-plugin-trait = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing", default-features = false } -zenoh-util = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "feat/tracing", default-features = false } +zenoh-plugin-rest = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", default-features = false } +zenoh-plugin-trait = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", default-features = false } +zenoh-util = { version = "0.11.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", default-features = false } [profile.release] debug = false diff --git a/zenoh-bridge-ros2dds/src/main.rs b/zenoh-bridge-ros2dds/src/main.rs index ab9ddab..ca32a4c 100644 --- a/zenoh-bridge-ros2dds/src/main.rs +++ b/zenoh-bridge-ros2dds/src/main.rs @@ -60,7 +60,7 @@ fn parse_args() -> (Option, Config) { #[async_std::main] async fn main() { - zenoh_util::init_log(); + zenoh_util::init_log_from_env(); tracing::info!( "zenoh-bridge-ros2dds {}", zenoh_plugin_ros2dds::ROS2Plugin::PLUGIN_LONG_VERSION diff --git a/zenoh-plugin-ros2dds/src/lib.rs b/zenoh-plugin-ros2dds/src/lib.rs index 8bc07a8..db998be 100644 --- a/zenoh-plugin-ros2dds/src/lib.rs +++ b/zenoh-plugin-ros2dds/src/lib.rs @@ -122,7 +122,7 @@ impl Plugin for ROS2Plugin { // Try to initiate login. // Required in case of dynamic lib, otherwise no logs. // But cannot be done twice in case of static link. - zenoh_util::init_log(); + zenoh_util::init_log_from_env(); let runtime_conf = runtime.config().lock(); let plugin_conf = runtime_conf @@ -141,7 +141,7 @@ pub async fn run(runtime: Runtime, config: Config) { // Try to initiate login. // Required in case of dynamic lib, otherwise no logs. // But cannot be done twice in case of static link. - zenoh_util::init_log(); + zenoh_util::init_log_from_env(); tracing::debug!("ROS2 plugin {}", ROS2Plugin::PLUGIN_VERSION); tracing::info!("ROS2 plugin {:?}", config);