From 5b85a236782555679b64d3f5222607bf6716fcc2 Mon Sep 17 00:00:00 2001 From: han J <89577994+owny990312@users.noreply.github.com> Date: Wed, 16 Oct 2024 19:39:38 +0800 Subject: [PATCH] Zenoh update to 1.0.0.11 (#31) * Upgrade zenoh to version 1.0.0.11 * Update the download link for the zenoh-c library to version 1.0.0.11 and adjust some related URL configurations. --------- Co-authored-by: hanjun --- CMakeLists.txt | 31 +- cmake/GetZenoh.cmake | 2 +- document/sphinx-cn/release_notes/v0_9_0.md | 2 + .../tutorials/plugins/zenoh_plugin.md | 14 +- .../linux/bin/cfg/zenoh_native_config.json5 | 336 ++++++++++++++---- src/plugins/zenoh_plugin/CMakeLists.txt | 2 +- src/plugins/zenoh_plugin/zenoh_manager.cc | 16 +- url_cn.bashrc | 2 +- 8 files changed, 310 insertions(+), 95 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 35987ac18..6c5d6ab83 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -249,7 +249,7 @@ if(AIMRT_BUILD_RUNTIME) else() message( WARNING - "ZENOH_PLUGIN: Rust compiler (rustc) not found, will not compile zenoh plugin. Please install Rust environment referring to https://www.rust-lang.org/tools/install.") + "ZENOH_PLUGIN: Rust compiler (rustc) not found, will not compile zenoh plugin. Please install Rust environment referring to https://www.rust-lang.org/tools/install .") set(AIMRT_BUILD_ZENOH_PLUGIN OFF) endif() endif() @@ -288,23 +288,20 @@ if(AIMRT_INSTALL install(CODE "execute_process(COMMAND \"${CMAKE_COMMAND}\" --build \"${CMAKE_BINARY_DIR}\" --config ${CMAKE_BUILD_TYPE} --target create_python_pkg)") endif() -# print all aimrt options -message("\n\n AIMRT CMake Options/Info:") +# Print all aimrt options +message("\n AIMRT CMake Options/Info:") get_cmake_property(all_variables VARIABLES) -set(printed_vars) +string(REGEX MATCHALL "AIMRT_[A-Za-z0-9_]*" aimrt_vars "${all_variables}") +list(REMOVE_DUPLICATES aimrt_vars) +list(SORT aimrt_vars) -foreach(var ${all_variables}) - if(var MATCHES "^AIMRT_.*") - if(NOT "${var}" IN_LIST printed_vars) - list(APPEND printed_vars "${var}") - string(LENGTH ${var} var_length) - math(EXPR padding_length "40 - ${var_length}") - if(padding_length GREATER 0) - string(REPEAT "-" ${padding_length} padding) - else() - set(padding "") - endif() - message(" ${var}${padding}: ${${var}}") - endif() +foreach(var ${aimrt_vars}) + string(LENGTH ${var} var_length) + math(EXPR padding_length "40 - ${var_length}") + if(padding_length GREATER 0) + string(REPEAT "." ${padding_length} padding) + else() + set(padding "") endif() + message(" ${var}${padding}: ${${var}}") endforeach() diff --git a/cmake/GetZenoh.cmake b/cmake/GetZenoh.cmake index 0ad374691..f56fe0224 100644 --- a/cmake/GetZenoh.cmake +++ b/cmake/GetZenoh.cmake @@ -7,7 +7,7 @@ message(STATUS "Getting zenohc...") # fetch zenoh-c set(zenohc_DOWNLOAD_URL - "https://github.com/eclipse-zenoh/zenoh-c/archive/refs/tags/1.0.0.6.tar.gz" + "https://github.com/eclipse-zenoh/zenoh-c/archive/refs/tags/1.0.0.11.tar.gz" CACHE STRING "") if(zenohc_LOCAL_SOURCE) diff --git a/document/sphinx-cn/release_notes/v0_9_0.md b/document/sphinx-cn/release_notes/v0_9_0.md index 4c5cb0579..8bc89a82e 100644 --- a/document/sphinx-cn/release_notes/v0_9_0.md +++ b/document/sphinx-cn/release_notes/v0_9_0.md @@ -3,6 +3,7 @@ **重要修改**: - 优化了 zenoh 插件: + - 更新 zenohc 库至 1.0.0.11 版本; - 添加了 zenoh rpc 后端; - 现在可以传入 zenoh 原生配置; - mqtt 新增配置项以支持加密传输; @@ -14,3 +15,4 @@ - 优化代码结构,移动代码 src/runtime/common/net 至新位置 src/common/net; - 升级 jsoncpp 至 1.9.6 版本以优化一些 cmake 问题; - 新增了 aimrt_py channel benchmark 示例; +- iceoryx 插件在编译前先检查是否存在libacl,不存在则不进行编译; diff --git a/document/sphinx-cn/tutorials/plugins/zenoh_plugin.md b/document/sphinx-cn/tutorials/plugins/zenoh_plugin.md index fecc525ca..7d839343d 100644 --- a/document/sphinx-cn/tutorials/plugins/zenoh_plugin.md +++ b/document/sphinx-cn/tutorials/plugins/zenoh_plugin.md @@ -32,12 +32,12 @@ | 配置项 | 作用 | zenoh_native_config中的配置值 | | :---------------------------: | :-------------------------------------------------------------------: | :---------------------------: | -| scouting.scouting. enabled | 是否开启多播,这将允许多个 zenoh 节点自动发现彼此 | true | -| scouting.scouting. address | 配置多播地址 | 224.0.0.224:7446 | -| scouting.scouting. interface | 配置所用的网络接口 | auto | +| scouting.multicast. enabled | 是否开启多播,这将允许多个 zenoh 节点自动发现彼此 | true | +| scouting.multicast. address | 配置多播地址 | 224.0.0.224:7446 | +| scouting.multicast. interface | 配置所用的网络接口 | auto | | listen.endpoints | 需要主动监听的地址 | - | -| transport.unicast.lowlatency | 是否启动最低时延,若开启将有助于提升传输速率,注意其不能与qos同时开启 | true | -| transport.unicast.qos.enabled | 是否启动服务质量,注意其不能与lowlatency同时开启 | false | +| transport.unicast.lowlatency | 是否启动最低时延,若开启将有助于提升传输速率,注意其不能与qos同时开启 | false | +| transport.unicast.qos.enabled | 是否启动服务质量,注意其不能与lowlatency同时开启 | true | - limit_domain 表示插件的通信域,其兼容 zenoh 强大的Key & Key Expression。如果不填写则使用插件的默认的通信域(即消息的 topic ),只有相`匹配`的域才能进行通信,具体的书写格式如下: @@ -67,8 +67,8 @@ aimrt: ## zenoh 类型 Rpc 后端 `zenoh`类型的 Rpc后端是**zenoh_plugin**中提供的一种 Rpc 后端,主要用来构建请求-响应模型。其所有的配置项如下: -| 节点 | 类型 | 是否可选 | 默认值 | 作用 | -| ---------------- | ------ | -------- | ------ | ---------------------------------- | +| 节点 | 类型 | 是否可选 | 默认值 | 作用 | +| ---------------- | ------ | -------- | ------ | ------------------------------------ | | timeout_executor | string | 可选 | "" | Client 端发起 RPC 超时情况下的执行器 | 以下是一个简单的客户端的示例: diff --git a/src/examples/plugins/zenoh_plugin/install/linux/bin/cfg/zenoh_native_config.json5 b/src/examples/plugins/zenoh_plugin/install/linux/bin/cfg/zenoh_native_config.json5 index 865de7a7e..e5641fc56 100644 --- a/src/examples/plugins/zenoh_plugin/install/linux/bin/cfg/zenoh_native_config.json5 +++ b/src/examples/plugins/zenoh_plugin/install/linux/bin/cfg/zenoh_native_config.json5 @@ -11,35 +11,92 @@ /// The node's mode (router, peer or client) mode: "peer", - /// The node's metadata (name, location, DNS name, etc.) Arbitrary JSON data not interpreted by zenohd and available in admin space @/router/ + /// The node's metadata (name, location, DNS name, etc.) Arbitrary JSON data not interpreted by zenoh and available in admin space @//router, @//peer or @//client metadata: { name: "strawberry", - location: "Penny Lane" + location: "Penny Lane", }, - /// Which endpoints to connect to. E.g. tcp/localhost:7447. - /// By configuring the endpoints, it is possible to tell zenoh which router/peer to connect to at startup. + // /// Which endpoints to connect to. E.g. tcp/localhost:7447. + // /// By configuring the endpoints, it is possible to tell zenoh which router/peer to connect to at startup. + // /// For TCP/UDP on Linux, it is possible additionally specify the interface to be connected to: + // /// E.g. tcp/192.168.0.1:7447#iface=eth0, for connect only if the IP address is reachable via the interface eth0 // connect: { + // /// timeout waiting for all endpoints connected (0: no retry, -1: infinite timeout) + // /// Accepts a single value (e.g. timeout_ms: 0) + // /// or different values for router, peer and client (e.g. timeout_ms: { router: -1, peer: -1, client: 0 }). + // timeout_ms: { router: -1, peer: -1, client: 0 }, + + // /// The list of endpoints to connect to. + // /// Accepts a single list (e.g. endpoints: ["tcp/10.10.10.10:7447", "tcp/11.11.11.11:7447"]) + // /// or different lists for router, peer and client (e.g. endpoints: { router: ["tcp/10.10.10.10:7447"], peer: ["tcp/11.11.11.11:7447"] }). + // /// + // /// See https://docs.rs/zenoh/latest/zenoh/config/struct.EndPoint.html // endpoints: [ - // "tcp/localhost:7447" + // // "/
" // ], + + // /// Global connect configuration, + // /// Accepts a single value or different values for router, peer and client. + // /// The configuration can also be specified for the separate endpoint + // /// it will override the global one + // /// E.g. tcp/192.168.0.1:7447#retry_period_init_ms=20000;retry_period_max_ms=10000" + + // /// exit from application, if timeout exceed + // exit_on_failure: { router: false, peer: false, client: true }, + // /// connect establishing retry configuration + // retry: { + // /// initial wait timeout until next connect try + // period_init_ms: 1000, + // /// maximum wait timeout until next connect try + // period_max_ms: 4000, + // /// increase factor for the next timeout until nexti connect try + // period_increase_factor: 2, + // }, // }, - // /// Which endpoints to listen on. E.g. tcp/localhost:7447. + // /// Which endpoints to listen on. E.g. tcp/0.0.0.0:7447. // /// By configuring the endpoints, it is possible to tell zenoh which are the endpoints that other routers, // /// peers, or client can use to establish a zenoh session. + // /// For TCP/UDP on Linux, it is possible additionally specify the interface to be listened to: + // /// E.g. tcp/0.0.0.0:7447#iface=eth0, for listen connection only on eth0 // listen: { - // endpoints: [ - // "tcp/localhost:50060" - // ], + // /// timeout waiting for all listen endpoints (0: no retry, -1: infinite timeout) + // /// Accepts a single value (e.g. timeout_ms: 0) + // /// or different values for router, peer and client (e.g. timeout_ms: { router: -1, peer: -1, client: 0 }). + // timeout_ms: 0, + + // /// The list of endpoints to listen on. + // /// Accepts a single list (e.g. endpoints: ["tcp/[::]:7447", "udp/[::]:7447"]) + // /// or different lists for router, peer and client (e.g. endpoints: { router: ["tcp/[::]:7447"], peer: ["tcp/[::]:0"] }). + // /// + // /// See https://docs.rs/zenoh/latest/zenoh/config/struct.EndPoint.html + // endpoints: { router: ["tcp/[::]:7447"], peer: ["tcp/[::]:0"] }, + + // /// Global listen configuration, + // /// Accepts a single value or different values for router, peer and client. + // /// The configuration can also be specified for the separate endpoint + // /// it will override the global one + // /// E.g. tcp/192.168.0.1:7447#exit_on_failure=false;retry_period_max_ms=1000" + + // /// exit from application, if timeout exceed + // exit_on_failure: true, + // /// listen retry configuration + // retry: { + // /// initial wait timeout until next try + // period_init_ms: 1000, + // /// maximum wait timeout until next try + // period_max_ms: 4000, + // /// increase factor for the next timeout until next try + // period_increase_factor: 2, + // }, // }, - /// Configure the scouting mechanisms and their behaviours scouting: { - /// In client mode, the period dedicated to scouting for a router before failing + /// In client mode, the period in milliseconds dedicated to scouting for a router before failing. timeout: 3000, - /// In peer mode, the period dedicated to scouting remote peers before attempting other operations - delay: 200, + /// In peer mode, the maximum period in milliseconds dedicated to scouting remote peers before attempting other operations. + delay: 500, /// The multicast scouting configuration. multicast: { /// Whether multicast scouting is enabled or not @@ -48,27 +105,31 @@ address: "224.0.0.224:7446", /// The network interface which should be used for multicast scouting interface: "auto", // If not set or set to "auto" the interface if picked automatically + /// The time-to-live on multicast scouting packets + ttl: 1, /// Which type of Zenoh instances to automatically establish sessions with upon discovery on UDP multicast. - /// Accepts a single value or different values for router, peer and client. - /// Each value is bit-or-like combinations of "peer", "router" and "client". - // autoconnect: { peer: "router|peer" }, + /// Accepts a single value (e.g. autoconnect: ["router", "peer"]) + /// or different values for router, peer and client (e.g. autoconnect: { router: [], peer: ["router", "peer"] }). + /// Each value is a list of: "peer", "router" and/or "client". + autoconnect: { router: [], peer: ["router", "peer"] }, /// Whether or not to listen for scout messages on UDP multicast and reply to them. listen: true, }, - // /// The gossip scouting configuration. + /// The gossip scouting configuration. gossip: { /// Whether gossip scouting is enabled or not enabled: true, - /// When true, gossip scouting informations are propagated multiple hops to all nodes in the local network. - /// When false, gossip scouting informations are only propagated to the next hop. + /// When true, gossip scouting information are propagated multiple hops to all nodes in the local network. + /// When false, gossip scouting information are only propagated to the next hop. /// Activating multihop gossip implies more scouting traffic and a lower scalability. /// It mostly makes sense when using "linkstate" routing mode where all nodes in the subsystem don't have /// direct connectivity with each other. multihop: false, /// Which type of Zenoh instances to automatically establish sessions with upon discovery on gossip. - /// Accepts a single value or different values for router, peer and client. - /// Each value is bit-or-like combinations of "peer", "router" and "client". - // autoconnect: { router: "", peer: "router|peer" }, + /// Accepts a single value (e.g. autoconnect: ["router", "peer"]) + /// or different values for router, peer and client (e.g. autoconnect: { router: [], peer: ["router", "peer"] }). + /// Each value is a list of: "peer", "router" and/or "client". + autoconnect: { router: [], peer: ["router", "peer"] }, }, }, @@ -103,6 +164,127 @@ }, }, + // /// The declarations aggregation strategy. + // aggregation: { + // /// A list of key-expressions for which all included subscribers will be aggregated into. + // subscribers: [ + // // key_expression + // ], + // /// A list of key-expressions for which all included publishers will be aggregated into. + // publishers: [ + // // key_expression + // ], + // }, + + // /// The downsampling declaration. + // downsampling: [ + // { + // /// A list of network interfaces messages will be processed on, the rest will be passed as is. + // interfaces: [ "wlan0" ], + // /// Data flow messages will be processed on. ("egress" or "ingress") + // flow: "egress", + // /// A list of downsampling rules: key_expression and the maximum frequency in Hertz + // rules: [ + // { key_expr: "demo/example/zenoh-rs-pub", freq: 0.1 }, + // ], + // }, + // ], + + // /// Configure access control (ACL) rules + // access_control: { + // /// [true/false] acl will be activated only if this is set to true + // "enabled": false, + // /// [deny/allow] default permission is deny (even if this is left empty or not specified) + // "default_permission": "deny", + // /// Rule set for permissions allowing or denying access to key-expressions + // "rules": + // [ + // { + // /// Id has to be unique within the rule set + // "id": "rule1", + // "messages": [ + // "put", "delete", "declare_subscriber", + // "query", "reply", "declare_queryable", + // ], + // "flows":["egress","ingress"], + // "permission": "allow", + // "key_exprs": [ + // "test/demo" + // ], + // }, + // { + // "id": "rule2", + // "messages": [ + // "put", "delete", "declare_subscriber", + // "query", "reply", "declare_queryable", + // ], + // "flows":["ingress"], + // "permission": "allow", + // "key_exprs": [ + // "**" + // ], + // }, + // ], + // /// List of combinations of subjects. + // /// + // /// If a subject property (i.e. username, certificate common name or interface) is empty + // /// it is interpreted as a wildcard. Moreover, a subject property cannot be an empty list. + // "subjects": + // [ + // { + // /// Id has to be unique within the subjects list + // "id": "subject1", + // /// Subjects can be interfaces + // "interfaces": [ + // "lo0", + // "en0", + // ], + // /// Subjects can be cert_common_names when using TLS or Quic + // "cert_common_names": [ + // "example.zenoh.io" + // ], + // /// Subjects can be usernames when using user/password authentication + // "usernames": [ + // "zenoh-example" + // ], + // /// This instance translates internally to this filter: + // /// (interface="lo0" && cert_common_name="example.zenoh.io" && username="zenoh-example") || + // /// (interface="en0" && cert_common_name="example.zenoh.io" && username="zenoh-example") + // }, + // { + // "id": "subject2", + // "interfaces": [ + // "lo0", + // "en0", + // ], + // "cert_common_names": [ + // "example2.zenoh.io" + // ], + // /// This instance translates internally to this filter: + // /// (interface="lo0" && cert_common_name="example2.zenoh.io") || + // /// (interface="en0" && cert_common_name="example2.zenoh.io") + // }, + // { + // "id": "subject3", + // /// An empty subject combination is a wildcard + // }, + // ], + // /// The policies list associates rules to subjects + // "policies": + // [ + // /// Each policy associates one or multiple rules to one or multiple subject combinations + // { + // /// Rules and Subjects are identified with their unique IDs declared above + // "rules": ["rule1"], + // "subjects": ["subject1", "subject2"], + // }, + // { + // "rules": ["rule2"], + // "subjects": ["subject3"], + // }, + // ] + //}, + /// Configure internal transport parameters transport: { unicast: { @@ -118,39 +300,51 @@ /// This option does not make LowLatency transport mandatory, the actual implementation of transport /// used will depend on Establish procedure and other party's settings /// - /// NOTE: Currently, the LowLatency transport doesn't preserve QoS prioritization. + /// NOTE: Currently, the LowLatency transport doesn't preserve QoS prioritization. /// NOTE: Due to the note above, 'lowlatency' is incompatible with 'qos' option, so in order to /// enable 'lowlatency' you need to explicitly disable 'qos'. - lowlatency: true, + /// NOTE: LowLatency transport does not support the fragmentation, so the message size should be + /// smaller than the tx batch_size. + lowlatency: false, /// Enables QoS on unicast communications. qos: { - enabled: false, + enabled: true, }, /// Enables compression on unicast communications. - /// Compression capabilities are negotiated during session establishment. + /// Compression capabilities are negotiated during session establishment. /// If both Zenoh nodes support compression, then compression is activated. compression: { enabled: false, }, - }, + }, + /// WARNING: multicast communication does not perform any negotiation upon group joining. + /// Because of that, it is important that all transport parameters are the same to make + /// sure all your nodes in the system can communicate. One common parameter to configure + /// is "transport/link/tx/batch_size" since its default value depends on the actual platform + /// when operating on multicast. + /// E.g., the batch size on Linux and Windows is 65535 bytes, on Mac OS X is 9216, and anything else is 8192. multicast: { - /// Enables QoS on multicast communication. + /// JOIN message transmission interval in milliseconds. + join_interval: 2500, + /// Maximum number of multicast sessions. + max_sessions: 1000, + /// Enables QoS on multicast communication. /// Default to false for Zenoh-to-Zenoh-Pico out-of-the-box compatibility. qos: { enabled: false, }, - /// Enables compression on multicast communication. + /// Enables compression on multicast communication. /// Default to false for Zenoh-to-Zenoh-Pico out-of-the-box compatibility. compression: { enabled: false, }, }, link: { - /// An optional whitelist of protocols to be used for accepting and opening sessions. - /// If not configured, all the supported protocols are automatically whitelisted. - /// The supported protocols are: ["tcp" , "udp", "tls", "quic", "ws", "unixsock-stream"] - /// For example, to only enable "tls" and "quic": - // protocols: ["tls", "quic"], + /// An optional whitelist of protocols to be used for accepting and opening sessions. If not + /// configured, all the supported protocols are automatically whitelisted. The supported + // /// protocols are: ["tcp" , "udp", "tls", "quic", "ws", "unixsock-stream", "vsock"] For + // /// example, to only enable "tls" and "quic": protocols: ["tls", "quic"], + // protocols: ["udp","tcp"], /// Configure the zenoh TX parameters of a link tx: { /// The resolution in bits to be used for the message sequence numbers. @@ -162,8 +356,10 @@ /// Number of keep-alive messages in a link lease duration. If no data is sent, keep alive /// messages will be sent at the configured time interval. /// NOTE: In order to consider eventual packet loss and transmission latency and jitter, - /// set the actual keep_alive timeout to one fourth of the lease time. - /// This is in-line with the ITU-T G.8013/Y.1731 specification on continous connectivity + /// set the actual keep_alive interval to one fourth of the lease time: i.e. send + /// 4 keep_alive messages in a lease period. Changing the lease time will have the + /// keep_alive messages sent more or less often. + /// This is in-line with the ITU-T G.8013/Y.1731 specification on continuous connectivity /// check which considers a link as failed when no messages are received in 3.5 times the /// target interval. keep_alive: 4, @@ -174,6 +370,7 @@ /// Each zenoh link has a transmission queue that can be configured queue: { /// The size of each priority queue indicates the number of batches a given queue can contain. + /// NOTE: the number of batches in each priority must be included between 1 and 16. Different values will result in an error. /// The amount of memory being allocated for each queue is then SIZE_XXX * BATCH_SIZE. /// In the case of the transport link MTU being smaller than the ZN_BATCH_SIZE, /// then amount of memory being allocated for each queue is SIZE_XXX * LINK_MTU. @@ -188,19 +385,37 @@ data_low: 4, background: 4, }, - /// The initial exponential backoff time in nanoseconds to allow the batching to eventually progress. - /// Higher values lead to a more aggressive batching but it will introduce additional latency. - backoff: 100, - // Number of threads dedicated to transmission - // By default, the number of threads is calculated as follows: 1 + ((#cores - 1) / 4) - // threads: 4, + /// Congestion occurs when the queue is empty (no available batch). + congestion_control: { + /// Behavior pushing CongestionControl::Drop messages to the queue. + drop: { + /// The maximum time in microseconds to wait for an available batch before dropping a droppable message if still no batch is available. + wait_before_drop: 1000, + }, + /// Behavior pushing CongestionControl::Block messages to the queue. + block: { + /// The maximum time in microseconds to wait for an available batch before closing the transport session when sending a blocking message + /// if still no batch is available. + wait_before_close: 5000000, + }, + }, + /// Perform batching of messages if they are smaller of the batch_size + batching: { + /// Perform adaptive batching of messages if they are smaller of the batch_size. + /// When the network is detected to not be fast enough to transmit every message individually, many small messages may be + /// batched together and sent all at once on the wire reducing the overall network overhead. This is typically of a high-throughput + /// scenario mainly composed of small messages. In other words, batching is activated by the network back-pressure. + enabled: true, + /// The maximum time limit (in ms) a message should be retained for batching when back-pressure happens. + time_limit: 1, + }, }, }, /// Configure the zenoh RX parameters of a link rx: { /// Receiving buffer size in bytes for each link - /// The default the rx_buffer_size value is the same as the default batch size: 65335. - /// For very high throughput scenarios, the rx_buffer_size can be increased to accomodate + /// The default the rx_buffer_size value is the same as the default batch size: 65535. + /// For very high throughput scenarios, the rx_buffer_size can be increased to accommodate /// more in-flight data. This is particularly relevant when dealing with large messages. /// E.g. for 16MiB rx_buffer_size set the value to: 16777216. buffer_size: 65535, @@ -216,26 +431,26 @@ /// or the client's keys and certificates, depending on the node's mode. If not specified /// on router mode then the default WebPKI certificates are used instead. root_ca_certificate: null, - /// Path to the TLS server private key - server_private_key: null, - /// Path to the TLS server public certificate - server_certificate: null, - /// Client authentication, if true enables mTLS (mutual authentication) - client_auth: false, - /// Path to the TLS client private key - client_private_key: null, - /// Path to the TLS client public certificate - client_certificate: null, - // Whether or not to use server name verification, if set to false zenoh will disregard the common names of the certificates when verifying servers. + /// Path to the TLS listening side private key + listen_private_key: null, + /// Path to the TLS listening side public certificate + listen_certificate: null, + /// Enables mTLS (mutual authentication), client authentication + enable_mtls: false, + /// Path to the TLS connecting side private key + connect_private_key: null, + /// Path to the TLS connecting side certificate + connect_certificate: null, + // Whether or not to verify the matching between hostname/dns and certificate when connecting, + // if set to false zenoh will disregard the common names of the certificates when verifying servers. // This could be dangerous because your CA can have signed a server cert for foo.com, that's later being used to host a server at baz.com. If you wan't your // ca to verify that the server at baz.com is actually baz.com, let this be true (default). - server_name_verification: null, + verify_name_on_connect: true, }, }, - /// Access control configuration auth: { - /// The configuration of authentification. + /// The configuration of authentication. /// A password implies a username is required. usrpwd: { user: null, @@ -257,11 +472,12 @@ /// Configure the Admin Space /// Unstable: this configuration part works as advertised, but may change in a future release adminspace: { + // Enables the admin space + enabled: false, // read and/or write permissions on the admin space permissions: { read: true, write: false, }, }, - -} +} \ No newline at end of file diff --git a/src/plugins/zenoh_plugin/CMakeLists.txt b/src/plugins/zenoh_plugin/CMakeLists.txt index 253335fea..b9c7ec731 100644 --- a/src/plugins/zenoh_plugin/CMakeLists.txt +++ b/src/plugins/zenoh_plugin/CMakeLists.txt @@ -34,7 +34,7 @@ target_link_libraries( ${CUR_TARGET_NAME} PRIVATE aimrt::interface::aimrt_core_plugin_interface aimrt::runtime::core - zenohc::shared + zenohc::lib jsoncpp::jsoncpp) # Add -Werror option diff --git a/src/plugins/zenoh_plugin/zenoh_manager.cc b/src/plugins/zenoh_plugin/zenoh_manager.cc index 1b9c96140..2fad81d3d 100644 --- a/src/plugins/zenoh_plugin/zenoh_manager.cc +++ b/src/plugins/zenoh_plugin/zenoh_manager.cc @@ -18,7 +18,7 @@ void ZenohManager::Initialize(const std::string &native_cfg_path) { z_config_default(&z_config_); } - if (z_open(&z_session_, z_move(z_config_)) < 0) { + if (z_open(&z_session_, z_move(z_config_), NULL) < 0) { AIMRT_ERROR("Unable to open zenoh session!"); return; } @@ -26,18 +26,18 @@ void ZenohManager::Initialize(const std::string &native_cfg_path) { void ZenohManager::Shutdown() { for (auto ptr : z_pub_registry_) { - z_undeclare_publisher(z_move(ptr.second)); + z_drop(z_move(ptr.second)); } for (auto ptr : z_sub_registry_) { - z_undeclare_subscriber(z_move(ptr.second)); + z_drop(z_move(ptr.second)); } msg_handle_vec_.clear(); z_pub_registry_.clear(); z_sub_registry_.clear(); - z_close(z_move(z_session_)); + z_drop(z_move(z_session_)); } void ZenohManager::RegisterPublisher(const std::string &keyexpr) { @@ -47,7 +47,7 @@ void ZenohManager::RegisterPublisher(const std::string &keyexpr) { z_owned_publisher_t z_pub; z_publisher_put_options_default(&z_pub_options_); - if (z_declare_publisher(&z_pub, z_loan(z_session_), z_loan(key), NULL) < 0) { + if (z_declare_publisher(z_loan(z_session_), &z_pub, z_loan(key), NULL) < 0) { AIMRT_ERROR("Unable to declare Publisher!"); return; } @@ -56,15 +56,15 @@ void ZenohManager::RegisterPublisher(const std::string &keyexpr) { AIMRT_TRACE("Publisher with keyexpr: {} registered successfully.", keyexpr.c_str()); } +void data_handler(const z_loaned_sample_t *sample, void *arg) {} void ZenohManager::RegisterSubscriber(const std::string &keyexpr, MsgHandleFunc handle) { z_view_keyexpr_t key; z_view_keyexpr_from_str(&key, keyexpr.c_str()); z_owned_closure_sample_t z_callback; auto function_ptr = std::make_shared(std::move(handle)); - z_closure( &z_callback, - [](const z_loaned_sample_t *sample, void *arg) { (*reinterpret_cast(arg))(sample); }, + [](z_loaned_sample_t *sample, void *arg) { (*reinterpret_cast(arg))(sample); }, nullptr, @@ -74,7 +74,7 @@ void ZenohManager::RegisterSubscriber(const std::string &keyexpr, MsgHandleFunc z_owned_subscriber_t z_sub; - if (z_declare_subscriber(&z_sub, z_loan(z_session_), z_loan(key), z_move(z_callback), NULL) < 0) { + if (z_declare_subscriber(z_loan(z_session_), &z_sub, z_loan(key), z_move(z_callback), NULL) < 0) { AIMRT_ERROR("Unable to declare Subscriber!"); return; } diff --git a/url_cn.bashrc b/url_cn.bashrc index d2c8e04ad..d7a888120 100644 --- a/url_cn.bashrc +++ b/url_cn.bashrc @@ -15,7 +15,7 @@ export AIMRT_DOWNLOAD_FLAGS="-Dboost_DOWNLOAD_URL=https://gitee.com/AimRT/boost/ -Dnlohmann_json_DOWNLOAD_URL=https://gitee.com/AimRT/json/repository/archive/v3.11.3.zip \ -Dopentelemetry_proto_DOWNLOAD_URL=https://gitee.com/AimRT/opentelemetry-proto/repository/archive/v1.3.2.zip \ -Dopentelemetry_cpp_DOWNLOAD_URL=https://gitee.com/AimRT/opentelemetry-cpp/repository/archive/v1.16.1.zip \ - -Dzenohc_DOWNLOAD_URL=https://gitee.com/AimRT/zenoh-c/repository/archive/1.0.0.6.zip \ + -Dzenohc_DOWNLOAD_URL=https://gitee.com/AimRT/zenoh-c/repository/archive/1.0.0.11.zip \ -Dnghttp2_DOWNLOAD_URL=https://gitee.com/mirrors/nghttp2/repository/archive/v1.62.1.zip \ -Diceoryx_DOWNLOAD_URL=https://gitee.com/mirrors/iceoryx/repository/archive/v2.0.6.zip \ -Dcpptoml_DOWNLOAD_URL=https://gitee.com/AimRT/cpptoml/repository/archive/v0.1.0.zip"