diff --git a/README.md b/README.md index a1d8c97fc..b44894756 100644 --- a/README.md +++ b/README.md @@ -220,7 +220,12 @@ Here are two ways to configure on the remote side: export ZENOH_CONFIG_OVERRIDE='mode="client";connect/endpoints=["tcp/192.168.1.1:7447"]' ``` -### Logging +## Security + +Security is available in `rmw_zenoh` by means of access control, authentication and encryption. +A `jazzy` port of the `zenoh_security_tools` package which contains a script to generate Zenoh configs with security configured along with documentation on its usage is [underway](https://github.com/ros2/rmw_zenoh/pull/661). + +## Logging The core of Zenoh is implemented in Rust and uses a logging library that can be configured via a `RUST_LOG` environment variable. This variable can be configured independently for each Node and the Zenoh router. @@ -232,7 +237,20 @@ For instance: For more information on the `RUST_LOG` syntax, see https://docs.rs/env_logger/latest/env_logger/#enabling-logging. -### Known Issues +## On interoperability with other Zenoh APIs + +The current scope of `rmw_zenoh` is limited to ROS 2 nodes on Tier-1 supported platforms and relying on a ROS Client Library (rcl). + +While it is possible for an application using any Zenoh API to interoperate with `rmw_zenoh`, supporting such use cases is beyond the scope of this repository's goals. If you aim to develop such a Zenoh application, you must follow the same design than `rmw_zenoh` for key expressions, data serialization format, attachments, and liveliness tokens. +See [docs/design.md](docs/design.md) for more details. + +## On interoperability with [eclipse-zenoh/zenoh-plugin-ros2dds](https://github.com/eclipse-zenoh/zenoh-plugin-ros2dds) and `zenoh-bridge-ros2dds` + +`zenoh-plugin-ros2dds` allows to bridge DDS-based ROS 2 communications (mainly using CycloneDDS) to Zenoh. + +`rmw_zenoh` utilizes Zenoh differently, particularly in terms of key expressions. Consequently, `rmw_zenoh` cannot interoperate with `zenoh-plugin-ros2dds`. This use case is beyond the scope of `rmw_zenoh`. + +## Known Issues ### Router crashes on IPv4-only systems diff --git a/docs/design.md b/docs/design.md index 43ecdc7a9..f2adff500 100644 --- a/docs/design.md +++ b/docs/design.md @@ -2,7 +2,7 @@ ## Introduction -`rmw_zenoh_cpp` maps the ROS 2 [RMW API](https://github.com/ros2/rmw/tree/rolling/rmw/include/rmw) as of late 2023 onto Zenoh APIs, using [zenoh-c](https://github.com/eclipse-zenoh/zenoh-c). +`rmw_zenoh_cpp` maps the ROS 2 [RMW API](https://github.com/ros2/rmw/tree/rolling/rmw/include/rmw) onto Zenoh APIs, using [zenoh-cpp](https://github.com/eclipse-zenoh/zenoh-cpp) and [zenoh-c](https://github.com/eclipse-zenoh/zenoh-c). The end result is that users can use ROS 2 to send and receive data over Zenoh, using the APIs that they are already familiar with. ## Brief overview @@ -13,7 +13,7 @@ There is more detail on each item below, but a brief overview on how this is acc * Each "context" in ROS 2 is mapped to a single Zenoh "session". That means that there may be many publishers, subscriptions, services, and clients sharing the same session. * Every "context" has a local "graph cache" that keeps track of the details of the network graph of ROS 2 entities. * Zenoh publishers, subscriptions, services, and clients are created or destroyed when the corresponding RMW APIs are called. -* Data is sent and received through the appropriate zenoh-c API when the corresponding RMW APIs are called. +* Data is sent and received through the appropriate zenoh-cpp API when the corresponding RMW APIs are called. The following diagram shows the default network topology of a subsystem composed of 3 nodes: @@ -28,13 +28,17 @@ flowchart TB classDef yellow fill:#a724f7,stroke:#000,stroke-width:2px,color:#fff %% DIAGRAM %% - Router(Zenoh Router:\n tcp/localhost:7447):::yellow + Router("`Zenoh Router: + tcp/localhost:7447`"):::yellow %% Discovery connections %% - Router <-..-> |discovery| S1(["Zenoh Session\n(Pub)"]):::blue - Router <-..-> |discovery| S2(["Zenoh Session\n(Sub)"]):::blue - Router <-..-> |discovery| S3(["Zenoh Session\n(Sub)"]):::blue + Router <-..-> |discovery| S1(["`Zenoh Session + (Pub)`"]):::blue + Router <-..-> |discovery| S2(["`Zenoh Session + (Sub)`"]):::blue + Router <-..-> |discovery| S3(["`Zenoh Session + (Sub)`"]):::blue subgraph Sessions @@ -55,23 +59,31 @@ flowchart TB linkStyle 7 stroke:green end ``` -Default Configuration for Zenoh Sessions: -| Config | Zenoh Session | Zenoh Router | -| :---: | :---: | :---: | -| Mode | Peer | Router | -| Connect | tcp/localhost:7447 | - | -| UDP Multicast | Disabled | Disabled | -| Gossip Scouting | Enabled | Enabled | -## Router +Default Configuration for Zenoh Sessions and Router: + +| Config | Zenoh Session | Zenoh Router | +| :---: | :---: | :---: | +| Default config file | [DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5](../rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5) | [DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5](../rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5) | +| Environment variable | `ZENOH_SESSION_CONFIG_URI` | `ZENOH_ROUTER_CONFIG_URI` | +| Mode | peer | router | +| Listen | `tcp/localhost:0` | `tcp/[::]:7447` | +| Connect | `tcp/localhost:7447` | - | +| Gossip Scouting | Enabled | Enabled | +| UDP Multicast | Disabled | Disabled | + +**The Router** is listening for incoming TCP connections port 7447 for all available interfaces (`tcp/[::]:7447`). + +**The Sessions** connect to the local Router via the loopback interface (`tcp/localhost:7447`). They also listen for incoming TCP connections via the loopback on a port chosen by the OS (`tcp/localhost:0`). -Zenoh has the ability to do discovery using local multicast announcements. -However, local multicast has some limitations, both intrinsic and specific to Zenoh: +**The Gossip Scouting** protocol is enabled to allow the router to discover the endpoints (IP:port) used by each connecting Session and to forward those endpoints to the other Sessions. As a result, Sessions can create peer-to-peer connections over the loopback interface. -* Multicast discovery can cause a lot of discovery traffic while discovering all other entities in the graph. -* Multicast discovery has a limited TTL (time-to-live), which means it can usually only discover peers on the local network segment. +**The UDP Multicast** Scouting is disabled by default. The decision to not rely on UDP multicast for discovery was intentional, aimed at avoiding issues with misconfigured networks, operating systems, or containers. It also helps prevent uncontrolled communication between robots in the same LAN, which could lead to interferences if not properly configured with different `ROS_DOMAIN_ID` or namespaces. + + +## Router -To alleviate issues with multicast discovery, `rmw_zenoh_cpp` relies on a Zenoh router to discover peers and forward this discovery information to other peers via Zenoh's `gossip scouting` functionality. +With the default configuration, `rmw_zenoh_cpp` relies on a Zenoh router to discover peers and forward this discovery information to other peers via Zenoh's `gossip scouting` functionality. Hence `rmw_zenoh_cpp` requires the Zenoh router to be running. It should be noted that when building upstream Zenoh from source, a `zenohd` binary is created which is the router. @@ -100,7 +112,55 @@ In the current design, `rmw_zenoh_cpp` uses CDR as the serialization format for * rmw_serialize * rmw_deserialize -### Related Zenoh-c APIs +### Related Zenoh APIs + +N/A + +## Topic and Service name mapping to Zenoh key expressions + +Zenoh inherently allows any pub/sub or querier/queryable pair to communicate, irrespective of their data type, encoding, or QoS, as long as their key expressions match. + +In contrast, to ensure rmw_zenoh_cpp aligns with the behavior of other RMW implementations, its key expressions have been specifically designed to + +* Prevent any communication between Sessions using different `ROS_DOMAIN_ID`, even when they are connecting to the same Zenoh infrastructure (i.e., interconnected routers). +* Prevent any communication between Publishers and Subscribers that use the same topic name but have different type names or type definitions. This also applies to Service Servers and Clients. + +The format of key expressions for topics and services is: + +`///` + +Where: + +* `` - The value of the `ROS_DOMAIN_ID` environment variable (`0` by default) +* `` - The [fully qualified name](https://design.ros2.org/articles/topic_and_service_names.html#fully-qualified-names) of the topic or service (i.e. including namespace, if any) +* `` - The topic or service type name, as declared in DDS (e.g.: `std_msgs::msg::dds_::String_`) when encoded in CDR +* `` - the topic or service type hash, as defined in [REP-2016](https://github.com/ros-infrastructure/rep/pull/381/files) and generated by [`rosidl`](https://github.com/ros2/rosidl/tree/rolling/rosidl_generator_type_description) + +Examples using the `demo_nodes_cpp` package: + +* `chatter` topic (with `ROS_DOMAIN_ID=0` by default): + + ```text + 0/chatter/std_msgs::msg::dds_::String_/RIHS01_df668c740482bbd48fb39d76a70dfd4bd59db1288021743503259e948f6b1a18 + ``` + +* `chatter` topic, using `/robot1` as a namespace: + + ```text + 0/robot1/chatter/std_msgs::msg::dds_::String_/RIHS01_df668c740482bbd48fb39d76a70dfd4bd59db1288021743503259e948f6b1a18 + ``` + +* `add_two_ints` service with `DOMAIN_ID=2`: + + ```text + 2/add_two_ints/example_interfaces::srv::dds_::AddTwoInts_/RIHS01_e118de6bf5eeb66a2491b5bda11202e7b68f198d6f67922cf30364858239c81a + ``` + +### Related RMW APIs + +* TopicInfo + +### Related Zenoh APIs N/A @@ -112,23 +172,80 @@ To deal with this discrepancy, each context in `rmw_zenoh_cpp` keeps a cache of An "entity" is a node, publisher, subscription, service server, or service client. Each entity sends a unique liveliness token as it comes online, and removes that liveliness token when it is destroyed. The key expression of these liveliness tokens encode information about the entity and it's relationship to the other entities in the system (for instance, a publisher is always attached to a node within a certain namespace). -The format of a liveliness token is: -`/////` +The format of a liveliness token for a node is: + +```text +@ros2_lv//////// +``` + +The format of a liveliness token for a publisher, subscription, service server, or service client: + +```text +@ros2_lv//////////// +``` Where: -* `` - A number set by the user to "partition" graphs. Roughly equivalent to the domain ID in DDS. -* `` - A unique ID to identify this entity. Currently the id is the zenoh session's id with elements concatenated into a string using '.' as separator. -* `` - The type of entity. This can be one of "NN" for a node, "MP" for a publisher, "MS" for a subscription, "SS" for a service server, or "SC" for a service client. -* `` - The ROS namespace for this entity. -* `` - The ROS node name for this entity. +* A mangled name is the name with each `/` characters replaced by `%` +* `@ros2_lv` - A constant prefix marking a [Zenoh hermetic namespace](https://github.com/eclipse-zenoh/roadmap/blob/main/rfcs/ALL/Key%20Expressions.md#namespaces) (i.e. `*` or `**` never match this perfix chunk) +* `` - The value of the `ROS_DOMAIN_ID` environment variable (`0` by default) +* `` - The Zenoh session ID (only one session per-context) +* `` - The ID of the node within the context +* `` - The ID of the entity within the node +* `` - The kind of the entity. Possible values: + * `NN` for a node + * `MP` for a message publisher + * `MS` for a message subscriber + * `SS` for a service server + * `SC` for a service client +* `` - The mangled SROS enclave name (just `%` if not set) +* `` - The mangled namespace (just `%` if not set) +* `` - The node name +* `` - The mangled [fully qualified name](https://design.ros2.org/articles/topic_and_service_names.html#fully-qualified-names) of the topic or service (i.e. including namespace, if any) +* `` - The topic or service type name, as declared in DDS (e.g.: `std_msgs::msg::dds_::String_`) when encoded in CDR +* `` - the topic or service type hash, as defined in [REP-2016](https://github.com/ros-infrastructure/rep/pull/381/files) and generated by [`rosidl`](https://github.com/ros2/rosidl/tree/rolling/rosidl_generator_type_description) +* `` - The entity QoS encoded in a compact format (see the `qos_to_keyexpr` function) During context initialization, `rmw_zenoh_cpp` calls `zc_liveliness_get` to get an initial view of the entire graph from other nodes in the system. From then on, when entities enter and leave the system, `rmw_zenoh_cpp` will get new liveliness tokens that it can use to update its internal cache. +Examples using the demo_nodes_cpp package: + +* `listener` node (with `ROS_DOMAIN_ID=0` by default): + + ```text + @ros2_lv/2/aac3178e146ba6f1fc6e6a4085e77f21/0/0/NN/%/%/listener + ``` + +* `listener` node's subscriber on `chatter` topic: + + ```text + @ros2_lv/2/aac3178e146ba6f1fc6e6a4085e77f21/0/10/MS/%/%/listener/%chatter/std_msgs::msg::dds_::String_/RIHS01_df668c740482bbd48fb39d76a70dfd4bd59db1288021743503259e948f6b1a18/::,10:,:,:,, + ``` + +* `talker` node's publisher on `chatter` topic: + + ```text + @ros2_lv/2/8b20917502ee955ac4476e0266340d5c/0/10/MP/%/%/talker/%chatter/std_msgs::msg::dds_::String_/RIHS01_df668c740482bbd48fb39d76a70dfd4bd59db1288021743503259e948f6b1a18/::,7:,:,:,, + ``` + +* `add_two_ints_server` node's service server: + + ```text + @ros2_lv/2/f9980ee0495eaafb3e38f0d19e2eae12/0/10/SS/%/%/add_two_ints_server/%add_two_ints/example_interfaces::srv::dds_::AddTwoInts_/RIHS01_e118de6bf5eeb66a2491b5bda11202e7b68f198d6f67922cf30364858239c81a/::,10:,:,:,, + ``` + +* `add_two_ints_client` node's service client: + + ```text + @ros2_lv/2/e1dc8d1b45ae8717fce78689cc655685/0/10/SC/%/%/add_two_ints_client/%add_two_ints/example_interfaces::srv::dds_::AddTwoInts_/RIHS01_e118de6bf5eeb66a2491b5bda11202e7b68f198d6f67922cf30364858239c81a/::,10:,:,:,, + ``` + + ### Related RMW APIs +* Entity * rmw_publisher_count_matched_subscriptions * rmw_subscription_count_matched_publishers * rmw_get_node_names @@ -148,17 +265,19 @@ From then on, when entities enter and leave the system, `rmw_zenoh_cpp` will get * rmw_get_service_names_and_types_by_node * rmw_get_client_names_and_types_by_node * rmw_get_topic_names_and_types +* mangle_name +* qos_to_keyexpr -### Related Zenoh-c APIs +### Related Zenoh APIs -* zc_liveliness_declare_token -* zc_liveliness_declare_subscriber -* zc_liveliness_get +* Session::liveliness_declare_token +* Session::liveliness_declare_subscriber +* Session::liveliness_get ## Contexts A ROS 2 context describes a certain middleware configuration, which can contain 0 or more ROS 2 nodes. -In `rmw_zenoh_cpp`, a context maps to a Zenoh session, along with a liveliness token for the graph cache and some additional metadata. +In `rmw_zenoh_cpp`, a context maps to a Zenoh session, along with a subscription to liveliness tokens for the graph cache and some additional metadata. Zenoh allows sessions to be custom configured through a configuration file. If otherwise unconfigured, `rmw_zenoh_cpp` uses a [default configuration file](../rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5). @@ -166,13 +285,14 @@ The user can use a custom configuration by setting the `ZENOH_SESSION_CONFIG_URI ### Related RMW APIs +* rmw_context_impl_s +* rmw_context_impl_s::Data * rmw_get_zero_initialized_init_options * rmw_init_options_copy * rmw_init_options_fini * rmw_get_zero_initialized_context * rmw_init * rmw_shutdown -* rmw_context_init * rmw_create_guard_condition * rmw_destroy_guard_condition * rmw_trigger_guard_condition @@ -180,15 +300,12 @@ The user can use a custom configuration by setting the `ZENOH_SESSION_CONFIG_URI * rmw_destroy_wait_set * rmw_wait -### Related Zenoh-c APIs +### Related Zenoh APIs -* zc_liveliness_declare_subscriber -* zc_liveliness_get -* z_open -* z_close -* z_undeclare_subscriber -* z_call -* z_session_check +* Session::open +* Session::liveliness_declare_subscriber +* Session::liveliness_get +* Session::close ## Namespaces @@ -210,58 +327,73 @@ When a new node is created through the RMW API, a liveliness token of type `NN` ### Related RMW APIs +* NodeData * rmw_create_node * rmw_destroy_node * rmw_node_get_graph_guard_condition -### Related Zenoh-c APIs +### Related Zenoh APIs -* zc_liveliness_declare_token +* Session::liveliness_declare_token ## Publishers A ROS 2 publisher sends data to 0 or more connected subscriptions. A Zenoh publisher does exactly the same thing, so ROS 2 publishers are mapped onto Zenoh publishers in `rmw_zenoh_cpp`. -If the Quality of Service durability for a publisher is `TRANSIENT_LOCAL`, a Zenoh publication cache will also be created with `ze_declare_publication_cache`. +The Zenoh advanced publisher API is used to benefit of some features that are implemented on top of a regular Zenoh publisher. +For instance, if the Quality of Service durability for a publisher is `TRANSIENT_LOCAL`, the Zenoh advanced publisher will be created with a publication cache. See the [Quality of Service](#Quality-of-Service) section below for more information. When a new publisher is created, a liveliness token of type `MP` is sent out. +A ROS 2 Publisher publishes messages calling the Zenoh `put` operation with: + +* the key expression mapped from the topic name +* the serialized message +* an attachment containing a sequence number, a source timestamp and publisher GID. It is encoded as such: + * 8 bytes for the sequence number (int64_t), encoded as a little-endian + * 8 bytes for the timestamp (number of ns since UNIX EPOCH as int64_t), encoded as a little-endian + * 1 byte for the length of the publisher GID (currently always 16) + * 16 bytes for the publisher GID (array of 16 int8_t) + ### Related RMW APIs * rmw_create_publisher +* PublisherData +* PublisherData::publish +* PublisherData::publish_serialized_message +* AttachmentData * rmw_destroy_publisher -* rmw_publish -* rmw_publish_serialized_message * rmw_borrow_loaned_message * rmw_return_loaned_message * rmw_publisher_wait_for_all_acked * rmw_publisher_get_network_flow_endpoints * rmw_publisher_event_init -### Related Zenoh-c APIs +### Related Zenoh APIs -* zc_liveliness_declare_token -* zc_publish_put_owned -* ze_declare_publication_cache -* z_declare_publisher -* z_undeclare_publisher -* z_publisher_put +* Session::liveliness_declare_token +* Session::declare_advanced_publisher +* SessionExt::AdvancedPublisherOptions +* AdvancedPublisher::put ## Subscriptions A ROS 2 subscription receives data from 1 or more connected publishers. A Zenoh subscriber does exactly the same thing, so ROS 2 subscriptions are mapped onto Zenoh subscribers in `rmw_zenoh_cpp`. -If the Quality of Service durability for a subscription is `TRANSIENT_LOCAL`, a Zenoh `ze_owned_querying_subscriber_t` will be created; in all other cases, a `z_owned_subscriber_t` will be created. +The Zenoh advanced subscriber API is used to benefit of some features that are implemented on top of a regular Zenoh publisher. +For instance, if the Quality of Service durability for a subscription is `TRANSIENT_LOCAL`, the Zenoh advanced publisher will be created with options to query the historical data cached by the advanced publishers. See the [Quality of Service](#Quality-of-Service) section below for more information. + When new data arrives, a callback within `rmw_zenoh_cpp` is executed, which takes ownership of the data and signals that there is data available. -Then rmw_wait can find out that there is data available, and the data can be delivered via rmw_take. +Then `rmw_wait` can find out that there is data available, and the data can be delivered via `rmw_take`. When a new subscription is created, a liveliness token of type `MS` is sent out. ### Related RMW APIs * rmw_create_subscription +* SubscriptionData * rmw_destroy_subscription * rmw_take * rmw_take_with_info @@ -278,31 +410,43 @@ When a new subscription is created, a liveliness token of type `MS` is sent out. * rmw_subscription_get_network_flow_endpoints * rmw_subscription_event_init -### Related Zenoh-c APIs +### Related Zenoh APIs -* zc_liveliness_declare_token -* zc_sample_payload_rcinc -* ze_declare_querying_subscriber -* z_declare_subscriber -* z_undeclare_subscriber +* Session::liveliness_declare_token +* Session::declare_advanced_subscriber +* SessionExt::AdvancedSubscriberOptions +* Sample ## Service Clients In ROS 2, services are meant to be used for remote procedure calls that will return fairly quickly. `rmw_zenoh_cpp` uses Zenoh queryables to implement ROS 2 services. When a client wants to make a request, it uses the rmw API `rmw_send_request`. -Attached to that request are various other pieces of metadata, like the sequence number of the request and the GUID of the client that sent the request. + +A ROS 2 service client sends a request calling the Zenoh `get` operation with: + +* the key expression mapped from the service name +* the serialized request +* an attachment containing a sequence number, a source timestamp and client GID. It is encoded as such: + * 8 bytes for the sequence number (int64_t), encoded as a little-endian + * 8 bytes for the timestamp (number of ns since UNIX EPOCH as int64_t), encoded as a little-endian + * 1 byte for the length of the client GID (currently always 16) + * 16 bytes for the client GID (array of 16 int8_t) +* the target option set to `ALL_COMPLETE`, as queryable for service servers are declared as complete + The sequence number is used to correlate this request to the response that comes back later. -`rmw_zenoh_cpp` then calls the Zenoh `z_get` function to send a query out to the network. -Assuming there is a service server listening to that queryable, it will receive the request, perform a computation, and return the result. -The result will then be made available to the client via `rmw_take_response`. +Assuming there is a service server listening to that queryable, it will receive the request, perform a computation, and return the response. +The response will then be made available to the client via `rmw_take_response`. When a new service client is created, a liveliness token of type `SC` is sent out. ### Related RMW APIs * rmw_create_client +* ClientData +* AttachmentData +* ZenohReply * rmw_destroy_client * rmw_send_request * rwm_take_response @@ -315,26 +459,38 @@ When a new service client is created, a liveliness token of type `SC` is sent ou * rmw_service_server_is_available * rmw_client_set_on_new_response_callback -### Related Zenoh-c APIs +### Related Zenoh APIs -* zc_liveliness_declare_token -* z_get -* z_attachment_get +* Session::liveliness_declare_token +* Session::get +* Session::GetOptions +* Reply ## Service Servers In ROS 2, services are meant to be used for remote procedure calls that will return fairly quickly. `rmw_zenoh_cpp` uses Zenoh queryables to implement ROS 2 services. When a ROS 2 node wants to advertise a service to the network, it calls `rmw_create_service`. -`rmw_zenoh_cpp` uses the `z_declare_queryable` Zenoh API to create that service. +`rmw_zenoh_cpp` uses the `declare_queryable` Zenoh API to create that service. The queryable is delared with the key expression mapped from the service name. As this key expression doesn't contain any wildcard (`*` or `**`) the queryable is declared as complete (i.e. it can send a reply for every request). + When a client request comes in, `rmw_take_request` is called to send the query to the user callback, which should perform some computation. -Once the user callback returns, `rmw_send_response` is called to send the response back to the requester. +Once the user callback returns, `rmw_send_response` is called to send the response back to the requester. This response is sent calling the Zenoh `reply` operation with: + +* the serialized response +* an attachment containing the sequence number received in the request attachment, a source timestamp for the reply and the client GID received in the request attachment. It is encoded as such: + * 8 bytes for the sequence number (int64_t), encoded as a little-endian + * 8 bytes for the timestamp (number of ns since UNIX EPOCH as int64_t), encoded as a little-endian + * 1 byte for the length of the client GID (currently always 16) + * 16 bytes for the client GID (array of 16 int8_t) When a new service server is created, a liveliness token of type `SS` is sent out. ### Related RMW APIs * rmw_create_service +* ServiceData +* AttachmentData +* ZenohQuery * rmw_destroy_service * rmw_take_request * rmw_send_response @@ -345,14 +501,14 @@ When a new service server is created, a liveliness token of type `SS` is sent ou * rmw_take_serialized_message_with_info * rmw_wait -### Related Zenoh-c APIs +### Related Zenoh APIs -* zc_liveliness_declare_token -* z_attachment_get -* z_declare_queryable -* z_undeclare_queryable -* z_query_value -* z_query_attachment +* Session::liveliness_declare_token +* Session::declare_queryable +* Session::QueryableOptions +* Query +* Query::reply +* Query::ReplyOptions ## Quality of Service @@ -360,18 +516,18 @@ The ROS 2 RMW layer defines quite a few Quality of Service settings that are lar Here is an incomplete list of some of the settings and the values that they can take: * RELIABILITY - * RELIABLE - Applicable only for subscriptions. Data delivery is retried until it is successfully delivered. - * BEST_EFFORT - Data may be dropped during delivery. Because Zenoh is TCP-based (by default), this may not work exactly the same as in DDS. This is the `SYSTEM_DEFAULT` reliability. + * RELIABLE - Applicable only for publishers. Data delivery via a reliable transport (e.g. `tcp` or `quic`), if such endpoints are configured. + * BEST_EFFORT - Data may be dropped during delivery. If non-reliable endpoints are configured (e.g. `udp`) they will be used. Otherwise reliable transport will be used. Note that with default configuration, only TCP transport are used. This is the `SYSTEM_DEFAULT` reliability. * HISTORY - * KEEP_LAST - For subscriptions, only keep up to a maximum number of samples (defined by depth); once the maximum is reached, older samples will be lost. This is the `SYSTEM_DEFAULT` history. - * KEEP_ALL - For subscriptions, keep all values. + * KEEP_LAST - For subscriptions, only keep up to a maximum number of samples (defined by depth); once the maximum is reached, older samples will be lost. For publications, if TRANSIENT_LOCAL is set, the DEPTH will define the size of the publication cache. This is the `SYSTEM_DEFAULT` history. + * KEEP_ALL - For subscriptions, keep all values. For publication, if RELIABLE, the `CongestionControl::BLOCK` mode is set, meaning the publisher will be blocked when network congestion occurs. This leads a periodic publisher to adapt its publication rate to what the network or the subscriptions can handle. * DEPTH - The maximum number of samples to keep; only comes into play when KEEP_LAST history is used. If `DEPTH` is set to 0, `rmw_zenoh_cpp` will choose a depth of 42. * DURABILITY - * VOLATILE - Samples will only be delivered to subscriptions that are active at the time of publishing. In `rmw_zenoh_cpp`, this is implemented via `z_declare_subscriber` on the subscription side and `z_declare_publisher` on the publisher side. This is the `SYSTEM_DEFAULT` durability. - * TRANSIENT_LOCAL - "Late-joining" subscriptions will receive historical data, along with any new data. In `rmw_zenoh_cpp`, this is implemented via `ze_declare_querying_subscriber` on the subscription side and `ze_declare_publication_cache` on the publisher side. + * VOLATILE - Samples will only be delivered to subscriptions that are active at the time of publishing. This is the `SYSTEM_DEFAULT` durability. + * TRANSIENT_LOCAL - "Late-joining" subscriptions will receive historical data, along with any new data. In `rmw_zenoh_cpp`, this is implemented for publications via the activation of a cache on the `AdvancedPublisher`. On the subscription side the `AdvancedSubscriber` is configured to query this cache to retrieve the historical data. * LIVELINESS * AUTOMATIC - The "liveliness" of an entity of the system is managed by the RMW layer. This is the only LIVELINESS that `rmw_zenoh_cpp` supports. - * MANUAL_BY_TOPIC - It is up to the application to periodically publish to a particular topic to assert liveliness. + * MANUAL_BY_TOPIC - No supported. It is up to the application to periodically publish to a particular topic to assert liveliness. * DEADLINE - The period at which messages are expected to be sent/received. Currently unimplemented in `rmw_zenoh_cpp`. * LIFESPAN - The age at which messages are expired and no longer valid. Currently unimplemented in `rmw_zenoh_cpp`. @@ -387,7 +543,7 @@ This means that any publisher can match any subscriber. * rmw_service_request_subscription_get_actual_qos * rmw_service_response_publisher_get_actual_qos -### Related Zenoh-c APIs +### Related Zenoh APIs N/A @@ -421,7 +577,7 @@ Events are broken down into subscription events and publisher events: * rmw_subscription_event_init * rmw_take_event -### Related Zenoh-c APIs +### Related Zenoh APIs N/A